From a1c05b7c6363c0977b8d84d1457be18dce83198e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Fri, 13 Dec 2024 14:12:36 +0100 Subject: [PATCH 1/7] First draf of async-client tutorial MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- source/Tutorials/Intermediate.rst | 1 + .../Async-Service/Async-Service-Main.rst | 599 ++++++++++++++++++ .../images/async-client-diagram.plantuml | 20 + .../images/async-client-diagram.png | Bin 0 -> 19672 bytes .../images/sync-client-diagram.plantuml | 11 + .../images/sync-client-diagram.png | Bin 0 -> 9524 bytes 6 files changed, 631 insertions(+) create mode 100644 source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst create mode 100644 source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml create mode 100644 source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.png create mode 100644 source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml create mode 100644 source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.png diff --git a/source/Tutorials/Intermediate.rst b/source/Tutorials/Intermediate.rst index 583bac4d6fa..dd54f74acfb 100644 --- a/source/Tutorials/Intermediate.rst +++ b/source/Tutorials/Intermediate.rst @@ -5,6 +5,7 @@ Intermediate :maxdepth: 1 Intermediate/Rosdep + Intermediate/Async-Service/Async-Service-Main Intermediate/Creating-an-Action Intermediate/Writing-an-Action-Server-Client/Cpp Intermediate/Writing-an-Action-Server-Client/Py diff --git a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst new file mode 100644 index 00000000000..577f1d84eec --- /dev/null +++ b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst @@ -0,0 +1,599 @@ +.. redirect-from:: + + Async-Service + Tutorials/Async-Service + +Writing a service with an asyncronous client node +================================================== + +.. contents:: Table of Contents + :depth: 2 + :local: + +**Goal:** Understanding asyncronism in the context of services. + +**Tutorial level:** Intermediate + +**Time:** 20 minutes + +Background +---------- + +For information on how to write a basic client/server service see +:doc:`checkout this tutorial <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>`. + +**All** service clients in ROS2 are **asyncronous**, in this tutorial an example of service client is +studied to provide some insight of that fact while explaining the reason for being asyncronous and some +consequences about timing. + +Consider the following diagram: + +.. image:: images/sync-client-diagram.png + :target: images/sync-client-diagram.png + :alt: A sequence diagram that show how a sync-client waits for the response + +It shows an syncronous client, the client makes a request and waits for the response, that is, +its thread is not running, it is stopped until the response is returned. + +On the other hand, in the following diagram an asyncronous ROS2 client is showed: + +.. In the definition diagram there is an invisible interaction, in white color, otherwise the activation bar could not be deactivated. + + +.. image:: images/async-client-diagram.png + :target: images/async-client-diagram.png + :alt: A sequence diagram that show how a async-client is not waiting but doing something else + + +In general, an asyncronous client is running after making the request, of course, it could +be stopped by invoking a waiting function or at any other blocking function, but this +diagram shows a ROS2 client, and, in ROS2 in order to get the response, the thread has to +be spinning, that is: it has to be waiting for any incoming events (topics, timers...) +including the response event. This fact is showed in the diagram: when the ``Event A`` is received, +its callback is executed (the client is *activated*) and, afterwards, the response is +received and the client executes the callback for the response. + +Since any service client in ROS2 needs to be spinning to receive the response for the +server. That means that **all clients in ROS2 are asyncronous** by design (they can not be +*just waiting*, they can wait while spinning). + +Thus, if a node **is** already **spinning** and has requested a service +**inside** a callback (any callback), the best approach is just let the callback finish, +you can process the response later in another callback in the future. You might find that +this approach is not obvious because the code to be executed after receiving the response +is not write inmediately after making the request, but you will get use to it, it +is just to write or look for that piece of code somewhere else. + +This tutorial shows how to write an asyncronous client that works like in the diagram. + +Prerequisites +------------- + +In beginner tutorials, you learned how to :doc:`create a workspace <../../Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace>` +and :doc:`create a package <../../Beginner-Client-Libraries/Creating-Your-First-ROS2-Package>`. + +In :doc:`Writing a Simple cpp Service and Client <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>` you +learned how to define a custom service that adds two ints, we will use that service again. + +The source code in this tutorial is at `rclcpp examples `, +you might get the code there directly. + +Tasks +------ + +1 Creating the server package +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +In a shell run: + +.. code-block:: bash + + ros2 pkg create --build-type ament_cmake --license Apache-2.0 examples_rclcpp_delayed_service --dependencies rclcpp example_interfaces + +Update ``package.xml`` as usual. + +1.1 Write the service server node +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Inside the ``examples_rclcpp_delayed_service/src`` directory, create a new file called ``main.cpp`` +and paste the following code within: + +.. code-block:: C++ + + #include + #include "example_interfaces/srv/add_two_ints.hpp" + #include "rclcpp/rclcpp.hpp" + + class DelayedSumService : public rclcpp::Node + { + public: + DelayedSumService() + : Node("delayed_service") + { + // Declares a parameter for delaying (default to 2.0 seconds) + this->declare_parameter("response_delay", 2.0); + + service_ = this->create_service( + "add_two_ints", std::bind( + &DelayedSumService::add_two_ints_callback, this, std::placeholders::_1, + std::placeholders::_2)); + + RCLCPP_INFO(this->get_logger(), "DelayedSumService is ready."); + } + + private: + void add_two_ints_callback( + const std::shared_ptr request, + std::shared_ptr response) + { + // Gets parameter value + double delay; + this->get_parameter("response_delay", delay); + + auto result = request->a + request->b; + RCLCPP_INFO_STREAM( + this->get_logger(), + "Request:" << request->a << " + " << request->b << " delayed " << delay << " seconds"); + + // Simulates the delay + std::this_thread::sleep_for(std::chrono::duration(delay)); + + response->sum = result; + RCLCPP_INFO_STREAM(this->get_logger(), "Response: " << result); + } + + rclcpp::Service::SharedPtr service_; + }; + + int main(int argc, char ** argv) + { + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; + } + + +Update ``CMakeLists.txt`` to build the executable: add the following +lines to it (after finding packages): + + +.. code-block:: console + + add_executable(service_main main.cpp) + ament_target_dependencies(service_main rclcpp example_interfaces) + + install(TARGETS service_main DESTINATION lib/${PROJECT_NAME}) + + +Then install dependencies if you need: + +.. code-block:: bash + + rosdep install -i --from-path src --rosdistro {DISTRO} -y + + +And build as usual: + +.. code-block:: bash + + colcon build + + +1.2 Examine the server code +~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. Note:: + + This package is NOT a real service server example, but an + instrument to experiment and understand the consecuences of + timing in services. It includes an artificial and **unnecessary** + delay in responding the requests. Nevertheless, it could be + used as an example if you remove the delay. + +Actually, there is no relevant items here. Only note that the +callback that attends the request is slept for a given amount of +seconds. The rest of the node is quite standard. + +2 Creating the client package +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. code-block:: bash + + ros2 pkg create --build-type ament_cmake --license Apache-2.0 examples_rclcpp_async_recv_cb_client --dependencies rclcpp example_interfaces + + +Update ``package.xml`` as usual. + +2.1 Write the service client node +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Inside the ``examples_rclcpp_async_recv_cb_client/src`` directory, create a new file called ``main.cpp`` +and paste the following code within: + +.. code-block:: C++ + + #include + #include + #include + + class AsyncReceiveCallbackClient : public rclcpp::Node + { + public: + AsyncReceiveCallbackClient() + : Node("examples_rclcpp_async_recv_cb_client") + { + // Create AddTwoInts client + client_ = this->create_client("add_two_ints"); + + // Wait until service is avaible + while (!client_->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_ERROR(this->get_logger(), "Service is not available, trying again after 1 second"); + } + + // Create a subcription to an input topic + subscription_ = this->create_subscription( + "input_topic", 10, + std::bind(&AsyncReceiveCallbackClient::topic_callback, this, std::placeholders::_1)); + + // Create a publisher for broadcasting the result + publisher_ = this->create_publisher("output_topic", 10); + + RCLCPP_INFO(this->get_logger(), "DelayedSumClient Initialized."); + } + + private: + void topic_callback(const std::shared_ptr msg) + { + RCLCPP_INFO(this->get_logger(), "Received %d at topic.", msg->data); + if (msg->data >= 0) { + RCLCPP_INFO(this->get_logger(), " Input topic is %d >= 0. Requesting sum...", msg->data); + + // Create request to sum msg->data + 100 + auto request = std::make_shared(); + request->a = msg->data; + request->b = 100; + + // Calls the service and bind the callback to receive response (not blocking!) + auto future_result = client_->async_send_request( + request, + std::bind( + &AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1)); + } else { + RCLCPP_INFO(this->get_logger(), " Input topic is %d < 0. No request is sent", msg->data); + } + } + + // Callback to receive response (call inside the spinning method like any other callback) + void handle_service_response( + rclcpp::Client::SharedFuture future) + { + auto response = future.get(); + RCLCPP_INFO(this->get_logger(), "Response: %ld", response->sum); + + // Publish response at output topic + auto result_msg = std_msgs::msg::Int32(); + result_msg.data = response->sum; + publisher_->publish(result_msg); + } + + rclcpp::Client::SharedPtr client_; + rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Publisher::SharedPtr publisher_; + }; + + int main(int argc, char ** argv) + { + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; + } + + +Update ``CMakeLists.txt`` to build the executable: add the following +lines to it (after finding packages): + +.. code-block:: console + + add_executable(client_main main.cpp) + ament_target_dependencies(client_main rclcpp std_msgs example_interfaces) + + install(TARGETS client_main DESTINATION lib/${PROJECT_NAME}) + +And build as usual: + +.. code-block:: bash + + colcon build + +2.2 Examine the client code +~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The code in this node: + +* Creates a service client: + + .. code-block:: C++ + + client_ = this->create_client("add_two_ints"); + +* Waits for the service server to be avaible at constructing the node object: + + .. code-block:: C++ + + while (!client_->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_ERROR(this->get_logger(), "Service is not available, trying again after 1 second"); + } + +* And creates a suscriber and a publisher (nothing interesting here). + +The node implements two callbacks, first one is for the subcription: ``topic_callback``, +the request is made here, **inside** this callback: + +.. code-block:: C++ + + void topic_callback(const std::shared_ptr msg) + { + RCLCPP_INFO(this->get_logger(), "Received %d at topic.", msg->data); + if (msg->data >= 0) { + RCLCPP_INFO(this->get_logger(), " Input topic is %d >= 0. Requesting sum...", msg->data); + + // Create request to sum msg->data + 100 + auto request = std::make_shared(); + request->a = msg->data; + request->b = 100; + + // Calls the service and bind the callback to receive response (not blocking!) + auto future_result = client_->async_send_request( + request, + std::bind( + &AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1)); + } else { + RCLCPP_INFO(this->get_logger(), " Input topic is %d < 0. No request is sent", msg->data); + } + } + +This callback check the topic value and, if greater or equals to zero, prepare a request to +the service using the new topic value and `100` as arguments, and make the request itself. + +The important items about ``async_send_request`` are: + +* It is called inside a callback, that is, it is executed in the thread that + is spinning the node. + +* It is not blocking, that is, it will return almost inmediately. So it will + not block the execution of the thread. + +* It provides a callback as an argument, ``AsyncReceiveCallbackClient::handle_service_response``, + that is where the code will *jump* when the response is received. + +* There is **not** any other sentence after it in ``topic_callback``, so the + execution will leave this callback and return to the spinning method. + +* Just remember, in order to receive the response the node should be spinning. + +* The ``future_result`` object could be ignored because it will be received + at ``handle_service_response``, but you might use it to track the + *state* of the request if necessary. + +The second callback is for receiving the server response. Note that, +being a callback, it will be executed at the spinning thread. The code is +quite simple: + +.. code-block:: C++ + + void handle_service_response( + rclcpp::Client::SharedFuture future) + { + auto response = future.get(); + RCLCPP_INFO(this->get_logger(), "Response: %ld", response->sum); + + // Publish response at output topic + auto result_msg = std_msgs::msg::Int32(); + result_msg.data = response->sum; + publisher_->publish(result_msg); + } + +The response is given in the parameter, `future`, it is obtained in the first +line and logged. Then, the response could be processed as required, here, just +as an example, it is published in a topic. + +.. note:: + + Compare to the code of an hypotethical alternative syncronous client the difference is where the code + to be executed *after* getting the result is written. In a syncronous call it is right *after* + the sentence calling the request, while in an asyncronous request it is at **another callback**. + +Installing the examples directly +--------------------------------- + +You might get the packages directly from code sources (clone the git +repository in a workspace and colcon build them) or if you +are using Ubuntu and you follow the `installation instructions `, +you can install them using apt for your ROS 2 distro: + +.. code-block:: bash + + sudo apt install ros-{REPOS_FILE_BRANCH}-examples_rclcpp_async_recv_cb_client ros-{REPOS_FILE_BRANCH}-examples_rclcpp_delayed_service + +Study how client and server interact +------------------------------------ + +Whatever you write the package or install directly the example, this section +provides some cases of study to show how client and serve interact with each +other and the impact of time execution in that interaction. + +Discover available components +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +To see what packages that contains `examples_` are registered and available +in your workspace, execute the following command in a terminal: + +.. code-block:: bash + + ros2 pkg list | grep examples_ + +The terminal will show a list of packages from ros2_examples, actually, +the list of packages whose name starts with `examples_`. At least you +should get: + +.. code-block:: text + + examples_rclcpp_async_recv_cb_client + examples_rclcpp_delayed_service + +Just remember to source the workspace if you don't. + +Run the delayed server +^^^^^^^^^^^^^^^^^^^^^^ + +Start a new terminal and run: + +.. code-block:: bash + + ros2 run examples_rclcpp_delayed_service service_main + +The service will start, in another terminal run: + +.. code-block:: bash + + ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 2, b: 5}" + +After a short delay you will get the response, return to the terminal +where you launch the server, you will have there two INFO log messages +showing the time at the incoming request and the time when the response +was sent. + +.. note:: + + As already said, this server is designed NOT to be an example, but an + emulator of a service that will take a significant amount of time to + compute the response. + +You might fine tune the timing by running: + +.. code-block:: bash + + ros2 param set /delayed_service response_delay 2.5 + +Being 2.5 the new delay in seconds. Kept that value as the delay to have +plenty of time to run next steps. + +Run the asyncronous client +^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Start a new terminal and run (source the workspace, if you have to): + +.. code-block:: bash + + ros2 ros2 run examples_rclcpp_async_recv_cb_client client_main + +This node doesn't make a request on launching, instead the call for service +is done when a topic is received, that is, the call to `async_send_request` +is **inside** a ros2 callback. So you have to trigger the request by publishing +to a topic, start a third terminal and run: + +.. code-block:: bash + + ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 5" + +Check the messages in both terminals, the one for the server and the one +for the client. You will find that, as you did manually before, the client made +a request and a bit later it received the response. On the server side +you will see exactly the same messages, no news there. + +Now, Why is this client asyncronous? Being asyncronous means that the +program is not stopped waiting for a result, insteads it keeps running +doing other things while waiting for the response. Actually, this is +the case of **all** ROS2 service clients because they all have to keep +spinning to keep the incoming response from the rclcpp layer. + +.. note:: + + In this example, the client is the part that is asyncronous. Applying the + term asyncronous to the server doesn't make any sense in this example. + +Let's try to see it in action, just run these commands one after the +other (if you are not fast enough, just set the delay time to a higher +value), copy-paste them to your terminal will also work: + +.. code-block:: bash + + ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 10" + ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 15" + +Check the client terminal, you will get something similar to: + +.. code-block:: text + + [INFO] [1733332216.902893640] [examples_rclcpp_async_recv_cb_client]: Received 10 at topic. + [INFO] [1733332216.902928394] [examples_rclcpp_async_recv_cb_client]: Input topic is 10 >= 0. Requesting sum... + [INFO] [1733332218.457559892] [examples_rclcpp_async_recv_cb_client]: Received 15 at topic. + [INFO] [1733332218.457593992] [examples_rclcpp_async_recv_cb_client]: Input topic is 15 >= 0. Requesting sum... + [INFO] [1733332219.403816764] [examples_rclcpp_async_recv_cb_client]: Response: 110 + [INFO] [1733332221.904430291] [examples_rclcpp_async_recv_cb_client]: Response: 115 + +Since the client **is** asyncronous, it keeps spinning, and thus receiving +topic messages, in the previous logs the topics for 10 and 15 were received at +a time ending in 16 and 18 seconds respectively, and the responses were received +later. That is, two request were done in a row before getting the results and +later they were also received one after the other. But, why the second response +takes more that 2.5 seconds? + +Check now the terminal that runs the server, you will see something similar to: + +.. code-block:: text + + [INFO] [1733332216.903081355] [delayed_service]: Request:10 + 100 delayed 2.5 seconds + [INFO] [1733332219.403276302] [delayed_service]: Response: 110 + [INFO] [1733332219.403700193] [delayed_service]: Request:15 + 100 delayed 2.5 seconds + [INFO] [1733332221.903918827] [delayed_service]: Response: 115 + +The server logs a message in its service callback, the client made the second +call at a time whose seconds are 18.45, but the message here is logged at 19.40, +what happens? + +Actually, it is very simple, the server is spinning, just like any other node +and this server only has one thread, so the first callback, the one with +arguments 10+100 **blocks** the spinning thread until it completes and returns. +Then the spinning takes control again, looks for another incoming request and +calls again the callback method with the new arguments: 15+100. Even if we +might think on them as parallel requests, that is not true, if a +**Single-Threaded Executor** is used, only one thread is used and, thus, the +callback are executed strictly in sequence. + +The key concept here is that an asyncronous call, like in the client, +does not **block** execution, so the spinning in the client gets the control again after processing the +callback with the request inside, that way it can execute the callback for other incoming +messages, including other topic messages **and** the incoming responses. +The client node is also run by a Single-Threaded Executor, so, callbacks are +also processed in sequence. The difference is that the callbacks in the client +return almost inmediately and so, apparently, the client is always ready. + +Another lesson here is that you should make service requests with caution, if you +make requests at a high frequency you should be aware of the efficiency of your server to +produce the responses. + +.. note:: + + Actually, in any circumstance, it is a good idea to check callback execution + times, since they **block** spinning and could produce unexpected and + unwanted side-effects. + +Just as a final note: programming a service server that takes too long in +computing the response is a potential issue in your system, this inconvenience +is a reason for using actions (among others). + +Summary +-------- + +You have create an asyncronous client node using a design that could be +used in combination with other events in ROS2: topics, timer, etc. Its +execution model is quite simple since the node is just executed in the +default mode (single-threaded). + +You have made some experiments about timing and the impact of +blocking callbacks and you should now understand better the meaning +of asyncronism and its impact in code design. diff --git a/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml b/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml new file mode 100644 index 00000000000..6d06e4574d4 --- /dev/null +++ b/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml @@ -0,0 +1,20 @@ +@startuml +participant Client +participant Server + +Client -> Server : Make Async Request +note left of Client : Client is spinning +activate Server +note right of Server : Server is running the callback +--> Client : Incoming Event A +activate Client +deactivate Client +Server --> Client : Return Response +deactivate Server + +activate Client +note left of Client : Client is running receive callback +Client -[#white]> Client : +deactivate Client + +@enduml diff --git a/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.png b/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.png new file mode 100644 index 0000000000000000000000000000000000000000..05bb58c1bfd7b0ad5dd46170de742f677eae565a GIT binary patch literal 19672 zcmeHvbzGEB-!7=IBC?19NQj7ngn-g5sFZ|sw=_t1ODPB_-QC??3j)&J-7MW5XV(5b z=XuZbp7`_p!Dp9ycjum&d*&P0b$#dK8xcN?Yk1d?kdQD0_+N@6AzgAoLPEB>dI?;S zx`}EDUMS38$(m~z8QU0WYMCSPX};4mRWsLodtcq=zK*%Mu^B53jj@5+J97&|18NN; zL(7g9BG81XuB5E_uj@$2pdIVTAn{g_OWZdqJ7vsgP@uTPD3i*Nc*YTae4Kfi+Pg>T zuT}ACh~FzbcpRo_mL?s4XVpMzT^4RJY$_4>+$cq?L2#37Tc+Z^ga8!<6C_>2e8QO7 zAbWVGn*YrFLMkf(Pm;eudCV4)!$STz^sU;L&RMK0Ou_UoPD;&s zKKjz&U4F3{i>?#HbHeT$&&=w&n8F!2pR6+`!mC=ubd8vJ<$8M+`e`z53r}5NK>|bL zW+(|}&W1kHyVCm!HcH{R)t{^|w8d7umT6FEG)#QZ;dD5-f@H*|1bvV!^r!xjwqYK_ z-{N!X6?g9H(QTpldad$R<96IYLK0jNc*!kkt-Kb6CM(r{d=ZB7wJ-4bjRs_Q{ukYa z1cK`pEpk0ny_ADOtqS25blOJOL{fDpB26E+61Q&!vk)^o-|Dy&@BE-+=S_#_#fsd; zzEOoI$~W%8iNzC}i6-rsz3i%i5xef=NQ)s)0#n4(-J~*pgAHDhrqYlgm%(c%Dl;y4 zv1Y7=ftT6>WGE_+*?ddU(vk@Y@7L@2jPixCVm^22rjPelTDUJ$n>RK3`Vg{+e`S$s z+MG^cdN-C?iHc-!h2XjyDXCW77n0%O;lZ!h@kZUyZUwobDynOcePmBr4&`!cu5USqodZ3`Ko@3H0+aBmxuk9*r6IDh7c8=aeea!ztDK^v1bI&aTLx5x4p4 z%k@^qyp8TjubobgSHieXa}5TwCDZJ`es~%{*7=4A=T$8X#eH^4qp9PGa%DKF`T6N1 z0RhkcJJC|Lu-FfXwu}kbwL2aV5vkD73rHIyyQwYA&$WB4yFmTt`bb0>f;`PfQ><&mKGozu1X!=$jV@J$=;) z3!;=svJwjm!x?TRWb@5bs*qAz3j>eA>nfNIpJ-Rz4SYQLfHm8GVyn%rxC9N23(BO0 zP8A+`42&%9)-$7;N4a%Q7j{cbllDxOtAo?iIei%i;gVdewhz|YzF`=Sm?sWZu?dgk z5GcN(CluO9A|N10779xe$?J+NHCP!Fj$*ajT^iclv^A^3s;o%*^unXHk}APc!KJrRhW9UTWJ$er(x+UzV|5D?XPDpor>JZOz(Hc3)sslg&? zyq${mYGc@#_VF{sY6*ubS6EVJ6__njOQ*={urkx_h=)DX1aoa7UL+DVVK}&+Ww3Hn zC_BiqKd0uL32ttWZD_VjP-!~v;dO_yyUo_tw&!+NV_=XODfK9;6*o6*Tl8gJy~>wp zq{FSId1~tHlYK%O9TG2RS8gn1u&}$$X$@6$lA@o^LM*)8lU^5QwAXQQgkG-7&MC4z3Nhqv z`)2&RbXumv`82s?mq$uAUUDIcc71s8=LtlH+l~wm+f3C?FW*KNhU6$$eUzT&bl^PN zZp9LR$tT)YObsJ)98zJ8S}t&B!-rB|Vul9uNlFrp)cFgt+zQDGuP|7-c#|*t^x$YG zBr!44)XFM`<0QpkeN~?^9;~?^i&z+lq>wX@9wPfB*hyw_%GYT7f#VMZVX z@zS=xjSRsFv}d&*D^2tD_1$&!rZX8%FVpBQHk^wvDo(&|2_$d5SLpbjcMcii`T()b z6Befq4>=wQvg2TNQ&GRuF5Z*z;5sXOKwp@ATp_SM>q}T6nR??f$Hy0o)QY9g6pF62 z5(-u1ft6`@kQ{KG-bv*u1m`yB*;~b>uDBhqJ1fH>?Tm&aVp;OWYaFfuiGm9eq0+1Z`&JN0mP!gO`D zS*_NWXJ*9HC3QtbMUSo8LYs%vAIYvy8IJA`rb$fJ*Vn^fYC8)`+sL^HGmz{GZ@*QQ z0A?=*P1CAEEP?dnN64=(JfK|3_w%D+cyQri!j1n0@^d$1G{LB#gsgdv4l~glc#~uO z-hqJxtdGdypO4vSMQ<1zbAu&?K7!F3ac|^GN@AqAw&61q(SfT!e=ZyibzA_me%sg8 z9pl%7Vji*w7M~xnJ*QN6z_PrLSeh=b?ck=)h*6_L8HtQ(k!~VP(?7qAMQF$l=?(qM zmOqu>$&o<2NnhNZFg^92oAZ{9NPnJoXSY#JR9xkCBm-oGcc7-8KG|S6cglYM)sKsM zJYUn>w9C15AWOmNSU2og%j@pLDdfx5rFI9|+s}}4QNVqpG+Tpx2-%ctaTzFVoBbcP zOux6^Y^ACBgr8Cwquy9DDN zLgiFnPN}M@s3tK|{-^g-&4dN-!%%pyKv97=jK%;H0DPtaa3@Ge&f1p=u7iKs@e!^4 z_04^hYM8n-Z9(maT3Bs$t)St5ejmW5h4Q1DwItZoip+X_sh>VwPn+wAVoTujyT|k{ zGBcR*i9)erp1ONJ{Uiaiv2%GxON%(E*FDSruZaQyj%Ry=o|r@w`s_*_kt}9A3&NV@ zNDC-X)G4g?2qr5Fi?iKc(Io!{ZyX7Mt(gYRqC%Ua`4Ai`*;uM}CSb6Oy}er(W1O;u zZgZIT(;rqloa`@k*N={Z1<8A`F)1T$>*eO@*%`qkDtFD<#>Exc`pR&sQiUZ=<>vc` zaoA7f3ymg~r>Aa_iF|EpB4ROpS*;n!cDO!Xks=Zm&p}VfWxaWyg@uKj{9{2$h3ULt zo_a&$r@OPWvk99jz+fsWj!jhAZH!m&(Ev+id$g@-RB(n#)#nQkV%4pFvSD@sj$oUbb{FaPGv z8)IYRdJha;?=s6Z`7}b7-elnnsSNCXGDtzTS=P*_PoH*ocJxOIb!BB`3$)r(KbNP9 zCwV7c`e8;on)zJH8{_46JEy^v#lS0w#VNlMqU5OFP0-kNkJ<9$X z$1~gPy@Ot`OM}=Cy7`DK*2lsKdy)7xKvWnz3odt8K=6ot;@*vybJ*>_J&_#w*uxvv z9}=6f-kXBi{EUoDd#cu@kDPFB*)JyiL69#VgI7PiC+T%GbUKmu5hC5(*0+M z-Mw24t0Sgd|ey8G|R98HxHlLA~iM=W@8D?dhQjE3?_cC-ZW=@++P-vG~tc|LApaF3*S_4yE)bb`GocvDn!Aa5LQ_nna_?YT*trR$L#KE1lQ& zbj}C0yK$%$tyi*2_+3`5dTeL?{QM5KxBW%9OlDppCYnNK1#ena)d*p{x)jnPF6O5u z9Z!5txp@;c%3PbB=5FrW&^$F5qAhc+xi~+$$6@Q{?*5ecDNA0b#a<~ez$GP2MqgJpIH)JM_#P2x2VvrJ|i`*T#B>fF%88H6DPPrGWw85r6%YcQ+9#sOiL zR!3x52A88=a7&VkTY$Oz2fBLG=&6Q(v>-$_9XJ~@QCKH3%*A3;K8?? zl6T`RMUEc`ac~Z%V3(z1wty=Md@S~!W2lYUYCW=`U?*Ft;+q1nznbo&B}OSc@YzYJ z4C$aJ3c;53ZT8oNA-!ApMwQ)p8ckdmrvbjr#><^a^H5TCb#)5K)aT-D{X|Y{BSpF= z(fSr3WP9=mVztyoOhMrl1Rl`$!GsSEfm?w1n0%X!^HIa z{P{C5O8%a=p~1^nP*9>+ExgNHa^$hGamU;y@H8Z9&P zPh{N<+Ys@IagO$NZ+24zw^@U^levQV4(hBcDJvJsd4t+s4&=wJxvSO`h?+1vt?$Bj;C9E z0@FyLxFF4|&jpqVOrPM%hPH1VjPc>qr(YP`$1AKR%gj=qL7YDVFHL)$5Lmh4f3kw~2{Ki};-uIOI9)_aHzau~B`r*wDqrMJV+S zSOm&d$CNph&-4eViZK@yf@4sgUqO7Y7KX}m6Sxdo!rk?8g{>3SYRw}#q?brg)O{2J zgWLSIt28d(n5wTG2G46F-#|v#Y-`h|8xKiIdnRP6wxnuHsJPIbuOd?Pyl)qi%`?B6 zMsgOL{!i~gtP(~=2m93o7@$=^+m*@uQ!1nfAkRLz1ZBKs-@09Z^Z^M(P3X)+LYq%o zJ1^b8WSqMecH@NTtAw{m6zjs=+~dXPME~+B+gJYx7i-q128U!%6c}4;Jhp^_!=`@q zX!J6Kt39^DVQ=L8k}hs2>aS53a~N;-UbifXQ#)}pl5@mH!g6*s#3VSSe^EZ#l}lLn ztE;kbxS(0(PX*_K^_JX2K>IS1q{oyZ}pI_GUOEwz0eIT(t z!COM+L|nHvjft4fU)vOj6Slj+gBBMR#U0^2k5&e<1Phn$tX{5aDy@Oej$Uf=SqFq`NNn7HRr{`YBAhF>=o zN?BM~uta0gFi`e)6M*@PUYw|iQBD)DJw)@f7iCIRD1nAU7d%Hwtw~$|+9aSeW~V&c zP0g!@dIGYAAdb2#y4P%JcaWtfmjCu+B4LeeX8Eygi?Q@kOTUBUnxx1ByRa130#U=1 zHEZ*>MZR99w3RnYQn4a@KKJfdCHf9YOHGS?pBaMJ(xR{R6=WX57%f z7L^_(pywMAngVvlBeiZ*+Tp?G<}{m~#_gf#(l+(}eoS=I{1&GPkvOehzlOXJ8`e;$ zqY6{aEAPhW=zBqw5Gv*PE!li6lx6dMD~&|fECs&ngd;K&R2c~@v{l>eok^Yi2u z;bB3*P@w!W5(ajC(BxG4BK3`ljnvjB^3V>}yjRt*AkXCNp;q9g78YeXZd^V31sm^^1eo1C-8Gub8la8XUny7PSxk4 zdja+01#gQA6Y%Ali`QO9MMd42BpU!v`S|1{_uvZH#Ku-M!DjNaJ8yq1z%f$cW#FKf zd*5b3)`1G;uyZX&vs5HVWssWR0{)-gOqzb2wIyHg=z5XsKkaJ5 zqAGS_gply)eGa{^m?Iv^iP_qi4@V#B&_#s>J&#c02-B5T^{sRu+v9Ix-RtcWCBvo( z!@KcDM5zO_$hH4bZRsBqKg~Aufp{{7vt71KZ{ZM4C0m*9WQDxGswyVtnT1<9l&h~% zDgWq%pI7z;J>y62|l&`l(W#P{L!cfryjh6b)a%o#s zo%I+gUB0QR_{+l$?bpI)-2QbZxwtl<6}h_nWs5IEyl)xjmi=~ez@_}lgw^#cgLi^`iStte{FPHq}tS9)Aql9 zpYg4+(U<4G7b~l|PDnri$pvioGQ!aUhxPFi3$D{Q!mZotL%E{ijAwS|4A&7KO$tA| zWlYOc7)w+@DRZ!>QjbV^z@U&JBrnnTHG-Wm>OpAY?Am^X;M0vKi9`kVdbmHL2QYLu z9pa0pt$x6!|M2zSf7IY77meoufD2v}DDMaCWgiG zN7G50(DS8)1AB)mPmGhnz%&xh^HRGay`VmeX!(~-_SKpzH-EH8{KHAUrcrTZne#-s z)!%P$Z*SSXJ)AIsxmaq$ra0k9L#um`79cFN6z=Amz#{^D+;FJ$Ifc#UW~jOS1^03E zT>nRb*0~4}7g}}8$z-p4k5+D;x{sS1!%g!m+ar5F0#nz#2;aU%p6ZsrdZ=@pENsH{ zXhX^DU_$H_L%U^1z(+5C!k~{T8cFY#Z{XIZ9G;~+LHX(pj=3mf6HOv&62jl6&TW3N z*hV%cu-_7YHvW|Lb$6*28+Mk+Jha-3$)_c0wBx;F+phZNl%GPefo`7c99J;n`EG(> z>2abfa6T&l%mAC`70WBV5s%o|T3|vj@CUZ`9nVXOE-vWwW9rFDmF=z(2so~;o}iTONaWEg7Ef~i@IfXmgw;Zi-^gQ^V5~@= zEnT3>+Pc&a|01ccRGBS2N)SpKRkJU@24b`IanX?Q7P`L4RzR#c#GM-<;fC>@{chk$Y@I$|(R9Gc9ODK{y&f&#vg%P`9-ErJjixTcH4ovW0S zMRuC!gqiPr%yJT$E$!+0SsX|Ox;b@C>l;z}7Gx4o3k^>W7TWO(OgSKacpT4JLmEj9 zzcP$=uLO=9%>_7hy?m{7`*Gh2CL#^kbGlqxI`kDL{<&UJG1BQ&_Zc~?x%uOOx{ZOT zec`a?==~$PLi-Sky|Fd6w3@7_gVUX)^)X?}F8KCmx2==%qbKt8$%K|5-t`XAVNc3@ z=Q*pIwh&Vyk;;B1OOT>Ct!hD74mfGiw8^$iw^KIR0){HPM=1SqHew}{$?cPR{kA4w zzd1@I`&u827t@xz9k}QDxr5b?PZ#$K<&u!<*5*-m!mX??2 zb{ZY6NoGh395?I(OY>?`)zYE|^~(hH5=-g3@o=*R-vDJ(`QAzy@my9fNSd$q*MQ0- zHadf$nr-vk(}Y<(hIG-Gr{TT6S}B=PN0UwaOIUZY_v06&c3xDSf6ps{Q;Po#tp-uL zR$EPH^k}oPe|=E9T)W3bM_QC7l z+cXBx_Yoy|7hIecZ1xySa}vtoVh3^zfwRKg@+c@__^Ve{nt9vV%>anBHer2v?iL5^wEPSE|q@Ot~XR z@nbljtpIW%S6xZNzz>-eAxg?ld#4S;^wuCdSZ8O`;GmuPuJ)^C)tjOj(!xv2Iy)R@ z(uD~LBqyxF50-e|yJnP@mHDTzWWmQNZ6ezycxSXZdN|ZJ0ys}r9c(9W-4rj<>-Rc4 z;hTp~RXbEjWiE*Z0g$vB7*RdN9Kv>yc^PgpR1}n!8p(kM_D_oc) z;neKL7)zeE60^$W6wDJTf)8uUyfT8JUoK3eb81e!jG66C|0}#w?)uhQ6>oJXO&5Po zR5+$4H)7r2b}|#EWFzsOfLw}WUu3Uud2b!ySHPq(n$X6_=9%`lZQZI?tkT*al<=^# zzG^|}ruDreND!`o*sQk~=VD*JJmEZy^ ztg49kkLSl)dvn2r^a-8d6RmXWAQ1viSiV4YHgR#qYP`00jEF^e&L)v)sZmUg4OSmt znUV7}{l0r#wDa3ux&Q*m8FBZ7-!b2R=l%Z_b;X^(1Go4U1^yFR_z~RvPU?R|Hh)19 ze^UGBgD`Y}UjoP~zi+WHMEY9AR}0 z>GRJ}aEZ0lW@q8-cuyi2n**S{3MKEPg0TtkoOE<_MDLQ5leY-E-)CpH2kdo=_}#x* z5hS2!_|cuuG>{lBr*l89^HP9V^6=C(2awJ8-{Z6o1t}B}k<)S?dDL1I9 zaqn<^?az>*QK_b)VR1O#T^lVK-g1Rt`UeE)vTtK#FVLob31`q338(*9o{aoD=+V+M z?>m%?T5Y&QL@_4^8TLot68wJ4?4mJbK6>nD+wlK6-h@`va)CysRusHt)T%fAf<0afnSw zEHwgBhX)Q-+L!@|J}qi$Y6?&|Y|PAxmDXY{&*%w(IwDf9KV5*vkAP)nb=7`7-|0vMX3Rt;SyXb)pvNmy>rHJfk3Q(^$; zs2qmc2}SJ2A9;hzDXTT$uvZTOR6AE085ud-qvsn0EARZTCHZO7J$tsKX=!Ph zUGybQA|-$O@X(r!j0{e)bTDCO1Q?N3*>zQm6mtM?tMT!D$C{ILMza>DWKhg}P|F6GFdQ8nf#FP=ZEF+Kdq_;IHmL&Q3R6JwlpWVkF^3kPQ&UqfcE+U4o}C<2 zl$Ymg+`se})U~}bg@TTqI}5Px08d{+Hr~buy{D6C()`)mJkmCc9Z_X|OgwDeV8gxc z*P(l|_vrh~B|BDCR-UsmFi}#z?u0FO#((s|X9@&`fk)btBncsO+cQNOgbVc z&}H6hv#Rl6pG2`)RofpuD=Pqaw=FbTO)-$zVVC3Ww;Omto}Nu$q)EqESXd85_E+@q z>=hLWe7IzsaKSRfr&V=6wpmqiJW6``@n%oKz*ms90B3KtHu5L~CHk&$?yrpW+Wge& zszFa&NQew@Q-UGX?dQpSf`WqW;S4I))9%kSTR!{gYG=Mn{0!x^+ov+5ma74bqN%xg zAe$fetd%tZJV8UxQyDNFEi1kF9{`^&5rMEJV13KV;-07nP0)fxdXIo$bzynD?=EJeDF$WeddOTh9Tc@Dq;SPyS~bzL0qq(fA! z;BB+Nvon$=Jiv5kp}nuK51{9dZ#`$fdF$2-9-iaMSwe^OeabjoEu4lrkL$G&(PYE_xQ20fk7>M}mWkeZISefWP-)wVMEQ_kTAm zJv3O34@E=!=qI%BL)_DmwElTtQgs&Zh6)XhGRRKE3)(JIn<;)j$pZfE3#vpW`REE(HD8?wJ1nuKc%VWi|q*<(9L_)bB-7{lUja z3LClpcM$bI1v&pE?*gKuA6ga<_g^3ufN}n}-UHAJ#BzVLJP3s8-v(n^mLLeUc7rDX zD+?qWEoFm{-#v2#ID^ah@PUx?Av8JhUb7rEuVc-q>PtMofAysF`88+?S<_y^9* z<%4ipTdx8P1O#Mul6?v)K6u7Un;V&x4kyXp*rHNIIP@Yh0_7$5KvPS(5$1SA6| z14N#~TW1isoxcnj>63tscb!p_ukK_kj}pb?E`4pz5PA z(3@NuXR}1??7Sho z7cB+iU8w+~Vz+-A75{z$9=?}EY|==A(w?t;{a#NFP-kF!zdD!r1Ao?56WH$z5Hm3i zvY0icg_!=|u|U-y|6i~`+p#NIlH~Uv%t+y>MX@q0tzEq^uR8AeyxSOX@djT;>Cz|k zpT0%~I+16_f;LqPo9y#0desWUeA2Wsn8N__bJ^(@DLM!Hmi#ApaFH6|7Nvq}@VGOY5|#pq^k!%NaIZrlu1rld50OENnyj3O z;7tI=c>K1a>SQ4Iv0VPk9$ytIX%2e;@nqP~FLS0_QjmSAYU_o~-5c@c`w0X2Hc*hY zU+aUXc3(~m>BAbuqhL?}!PRh>A6g-z#dG$$7OOSov_)0%RSzHZRQDWS44u*a4Im3k z=IH>-;E5lbEXO^In#eb7zqusv?1cmqEZEgr)%Vm5e=J` z$%4XxRs=+FdvH2l%JAS^P0AD|NH~-;8cTFTCJ{Z(Yv0@ErNI&P5rNlCv+LiwUIN2TIcBSnzF#Y=%1iWT0ud<%*j{VJE;;*PDK0B zssKS>UvDrK;bQIRO^Dn+jT}uBIO~W~P%4iUx~$)IU$GZPCh{)Hbl;67YJOHi+BAIu z9(im``;F{p6f@2;q+TTR=1nY6V&vqML`3MX3}7vjMI>sB)QX|d&~z^MQvxtfQFh3C zHG+qL<1>S+YsQ<_Is8|HnR4lG%FUa%=N(?Wa9x@jg(uwZ-=%ny;&5V_A=@2exdRf} z$@aUHM$+luX}{A*yM>8$WB;Z*6Yo;JB|^OeV~>CLkRof8L}#+Ybng7qttT!N^XHB+35LZ(@q_-w{*7VQ?u`k@9~>Ow9l!pI&QU%th<5NN0f~@ryOpKP-~- z87qRN!uc;*Dza-fwrV{8LOdlN{x5hc6vx}!yLEtq`kR)*Ra^LnSwVu3v=RJc6W7A7 z(s_=+YJc;;v~_L3hT{JaBGisS?|J0z0G;w@g#fT2PC!PAz&aB6FpZ2hczy5y{ih-aH>srM+kNn?S9t z&JA+?SIOoHNVMkW<`NSh>dx97ZO;Q}qla{_FHHgfJ+b~kzd2E6#+NQSkL~SV#qM-| zN(3YwKobV;E}^-2;-;g+*dXKq3wKK4&Vw3AQ;R| zNzqnSy}#z6n<4n<{QMk%8LBCtotwiSD((AQ7D_gCcIJSbqcwykB?Odyq>CpBf|s%J z@f6{R#`I?LC2If|;oiL~pajSndMc_+xdN@sXM6oc`Z9QAQu~{mxLl6xl#@T8n8)~d zc!DG>)|;`CDrN@ZYx=&4pMOV8xikjzQ=AURpBcvNYcoF|Xys`dsH<|y{B z-)3n9VuzzykgzRacfruHsXptqs7wF_vEDs4OQDu$(W>k~RifV=?+%{dd`nOWm0aCO zTy^!yI$PQ>NRu%MS?M`BCmI@FQM}a{Dl;R?$YEl9brSjI_HUsQYHTfi$l3WGSaO;z zfnh9Wq=bltHG)o&s!*~%R%VtI(w{D+P-V-&CL$tI9OP=Y!*Q<>q}MGM7c|)C z768(h-vUq_D@#i)ObQ8=LT>G3gp$0Xf~_pLBi_dXD2Uim43mnq@h8BeDZ!W#zw+1ubaW3vIu3+2+w^WK9n@iOjya3F%x4R2!e4vz~0s?7r1qwx6zjN;(eL=rvF=d$>CG_f8e-($44i;R4bFfTRSXQNM-t^-1nK=iLKJUQl_V zO>_x|VR@_T9zD<;T4v0NqN z{k=X{(S2QYXGe3@UZ_yU#l_K7AI2-84So1)zw|+a8LQi>Ujl&YzUqrVotWd->PJ8t zyE$VpU|%NfcQA&-eZvY&s21{!l;hax9Tlqu8EqZd21#NY4>PN&)qG2Je)I$H>muoI0-1p&J zhD8UW*2@0*AN+#k65>|~4aRjqZy+i#grJC7q`d)d`~Y!t#7xyb2V%tU^%$n#;Zmen zenh9g>pPH~AH0H3q2<-zxC)y+JE%ZN4js++zWX4=XKPc$!DH92@XX(AKe6F1LYi7XWeH~0&~<5+d}m|;C5dE&=i8{cb0E|+(cyM=ViN+A$A!` zcpep0Vl-*qJ(IRP`@RuQC&2XXo_L7DwZY6R9=E5)Ghx?7mnA3cT7z?FRGz+2DtrD# zn`Ajg-1qwcTwH)&rS<~=?gxzs48{)c7;P*z!vaV#*9LPSgauOh%2l~?1sbwNfKe+k zP>Sc|;KI6h-ZN%1+dm&%$Dp5aL+yH`HEDf7vhq3I=5{MF7gcC#wqoqJ0<88JaSn_f zgq#!U`4@j0$iGWXxAqP|=v8vg+~&K%#XlKP$@)|`%-+gw{ggW07)Un{-Clv%G^m9} zNhDj2&Uz-17^o*CNW{y^hZEotj16ajl~(QJc6@jG6ZdruKwg^vTWHbqIrYplcvf6^ zkAJrXp{~%#tCkxsUt9dtb_ixsOl3ERosvt5lfT_gGtY7V`CtW$BQe9HJ9^T=9(?UR z?SV}GW~^JCqvW<^=`RX;e=990XP6IXlHQiHvc8_k*CN5ry7xw7jx372g1{ocOk=}A zpk5uu=pTf6@AOMb3ZJT~%?QT95?0zUN>(3W;eZ}GoY4>$dtbdk%jb5#?1?#R|4&&) z+SkcR?K2M|+2CMP2n3RUJ0p$dW|gVC7X8X+3xMp(mAn%!-<+tLjH?D3M-rlF^K$#o zwg(hzOT6W6UU$wS=+ibrUJ-xzA6v zh3wSQxJPXN*PeVL;e zch`c@{|bxNsT*HQ99vhG0>sxfiF#BxQd_?rh`LcA3nP!w2H zAI`XfYE)OVcy@ZWBH0c6jOX)&Y>Y(oOE31tJ7K%)bK5~x<^(ah-}?LKt$8bzNo+Zu zL3%&#I`ZIIp1;^K_-=20JamL2v!@v-GM5`VK+^cB%{pClW#b>pi;?5K!0F6qWuMcd zS_IzG?3mL&nJFan^F2D%IVQCr#O|vu+){^`I=&*zi*aE6Z{_T7o$5wa8 zr!^zlc`l=rHwEyfnW0v8LLo>^PQ+yVD~*vwsceE=>yM2ZwcGo0#srx^7Gj^pQhHS- zdy*qv!A(%#DKc0gBe^~^lgTWWlRv*T{bgA&$aZ}{s&8_j!|wb@9EdngL?jDy)&t{( zBWn87_hvqPIZGBI+*+?NOr!Z%NrtV@(jLFhl`DbhXlX6`y(k#WL!2O3gFGNp_HeICwZS|>hK!OSywj2CrdJSMvyDchBh2w5 zzc(C__fy9GGw)wC5>ZW4|-&dy@Ejl@IM&@83dKmnV%>VdExyY5xTnGEk zUT}lnI!N>HM7hFCfnchy0pNS|eW)09J3xeeUS&J$V+&TeHqpCY3~kH7j7;l@XK(o@ zflAiax^!ct%74=PL0?ofb6F6z8^>kQ5csSFqbTI$ubYD%lSBOA(UgdvYY^ z-a3(>ewTrseyMGku;=OykWD%OmrMezzCz}T?!Q0>t8)0DoJCOZ&R^P$2sM>QJp~~R z>HXgoti!MWQn0GX2f}|q2e;P>hMcAbP3M(2cXr~`{Cv+d`3Z&6b^6oMlo$-FwL83$ z?e{;rO$Hn>tLHaK@@qE3PxJllLHlukgG>gfOl?PN5z|ud;i!fxF~E z8Lc*u5ve`5^U@+^k!Ce{G`q}V;M1s;xL;zX1ban??#povwM*b`n?l&M4^Yf#-`}E? zX(!;CZtd6C0xGQ1l7k(fO?orP&F+q<4&_CL7Rz;YEG}FsvQ2S?)Tr{09^e)st|sz18SQ%Emz%gs_}MW zF1`*uM7@3}u5|eJsb1gE)-0KFjiVBaPOba;5I9)_zMf{Jt5)YhcVhk0Xd*K9*AX0A zt3yL1eE9_hIUn!R7Y_{yAdc(+0FQ_OmX%2V*4Y6UjeMc3&0VCSOW>4<_77Oy%M49PKsYA8Zbkn>9oK2`Q-rKJWJl;40(U%aKyzSAB}XD z;pjI|la(&oscpV-ejdwB(*NuH3`*(D6tpK2jTItM$1W~G;Gl^^t8-l-XZv-4hST|x zjJEdT!Q{mUOOZ^sec0NlRZClC;903F`duun_KTxV&Sg__(9`(Esg|IOo{H4AHt*GW zUqZft?D6#MeIX#t`gMRn;Q=^yquH`*`7@jKQdf6g-bIl3&LRzQmWRhc?EHDj znhTEI2%~Czw*8gOO_}9>JK=O9LXIz%T5}$ZhOFYN6H&?Q=uqm%;n3s*aVQijk=!N@ zPOK17EVfur7K!4pH8-%ft^x`MkeN1!iB-*$`4U~UJ0rVZ>-%tOjtvgH0Ovs<4!qzr zzTey3Z8FF2lN9Mb2HV!~*9SG?5DdIBo$ho|uCt!;afk8pHOYxs*ovd$x#1{pM_7Rl zI64A=9Fi_A7Y8-%40>+e=^Pr32e-+|S(d92lK@xsa(4DoQ=0}AoNX=Tnf!2JM9=IU zTDz&7PSz@qcAR|uCSOpi)Np>$6pbtu&yJk@fTaOC7k^*?jwQH@IB5W!OrcZ}G%#Fd zhLa&dMNb$RW|JlqmJjBdIZZxAWTROBK)TohjdW13VtG*IBEp=N)4Q0(7OGrk`l7)r zNJk3@`*g4AXtcC|Gb;?EDq>?*kH{W?!%g@_k$}p<6bEO};lvlG5DT35^5a++9oEod znnLl;&@ETi2A*CRKI6k~xs9p=(UHr08(g_6H8glkzE{!E+Q9)Crrnk+0|lC`jH|d% z#9fo`qi4(A;v1C?#|qD!sN(8a`2H|-s^@$@-K8rt7{(b2KnBYup2(R@=Os9#;MWrn z5$0H1U1c|(GX8!72v7sO%rK7OjIlqOze*mTK&GV-GKI;tN)sirH(VEm0l`5gfV7fO zq+=SY2_!{+Y?W?TD&BK?ESDL2a(eVyTwJ8AqM|eUOoGvBp8;PCANj^S4+nR>3QiJ}nJe^U- z?RKV7F?0ZXX=2KAag%KSKE1@u*#0#7=A&ru4?5U5C3K_5l=U%=@>qEC5@+KNk4&0; zl_(^y21b94GXrpLSeE>IP*XoH3sz>8U9SLYcnyu)_hT^Vo>7}Gb=fp{?X9+IMKG?V zN&HX>YSbeS`$i3&aUB zy9*yD#K7$Jy5(1lr-}u9{p$Lw3txgPhMSr~@V+?Jm;QAeh{vodwkI@7wuaNB^PZ2< z`tmD5L1>hJpgI2;VJO*E=F(WOq)^s8;KG=O? z)jWo`cR=|%tfsH0B=cN3IvxLR64)G5~o=Sl6#!27}A PDw4n}k(b##s_*{?Hegm4 literal 0 HcmV?d00001 diff --git a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml new file mode 100644 index 00000000000..ba144d10d89 --- /dev/null +++ b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml @@ -0,0 +1,11 @@ +@startuml +participant Client +participant Server + +Client -> Server : Make Sync Resquest +activate Server +note left of Client : Wait for Response +Server --> Client : Return Response +deactivate Server + +@enduml \ No newline at end of file diff --git a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.png b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.png new file mode 100644 index 0000000000000000000000000000000000000000..03bcba0fdf67cc562cc72d3e368c45437fa92ad5 GIT binary patch literal 9524 zcmch7by!sG*Y3(uRuTBe;dWck&BDpq+uqX34Wwx4Xz60+X8C}@+?(N{o13%iEnZ${doxEjcL#eO z3nvGUfgXCm46V&wJ-5G~gTR0tuMDGDHH}sz(bKIn&L23>;3^#Pbk~U6p@u9)Gu{rb zADE{W)m5k+A2~8B?N_EB&8JT4i+<8MFS}v2(D{prfM}`<>Qh%Q5I)Y zUCmQ;9c*L2cW5*8^v05Le{g-Sd*3Qe^+)b|7B7Cu_G+T(JXAcZ;8+8aZwS!P0h4jw-(-x3))!zFrC{TyBuo{QmV!(kgYVZfFx}@1-FK#GHYWm$~a@ypaj> zQu{j5Dfa{?oHI>H>GSjWA56j2CMe%@-zaXz;Hh^y*XWDv-qDJQ+5vbB9f z6=A0=%b9Ietop#Y&$jRo?%>)OF!f-dkU1*~>VYVWqh7pw?ST5H~Co$cz>Nz7>Q(mlDK-GG*XMJ!}+u0C2o82!XVYg%XXn zq@bTXu`>y1*htVI=P_yAd`9mQeER(Pv6!p&!Xld)0;~i4M9{kURleiLU>?INR?fBQ zT>@eLc#vUh9J(W-X?J_OP`|=zZPWn+^1}Vm+uhG94Fj2VA^E_crk#&`qea$(Qf*J8 z5~m%r8!k_W!bo0suVMalGa70?R!Tx*P-1*hWs8|sPZ;g_S08**^*N~r0QKuP3uQ3~Y6$ z>C4Re^g{)>sY)UO#2KKesZ#Z$SB(ptz}7jCc91$0e2qklmUIN-^sUOlSAVf?OZ{?x zm=_M0g27Hy9xl7eUe(mZl<~}dS^vZg_gK~}KGz49AsYdXbzx(BUF#~HBEo+st!822 zc3D}4tgP(WQGmnB=aJ>**}1y-cqv*DM<#3N2}Ar6l@i20LLVmjD5q3APkA_>r7Qh; z7z^^gg8kPwS{N&fx+V@jXB$UGMn<0NV=<=$w8q=JyC0Lm=@BrJd?w7>*dqaF4n7g& zEnZIA+Ks`M)+Vvi5r}3E;IT&E#5p-Tcjc?qMT9#lrHPU(t&D^2NCaGdw(K3XdO-6u zdi{H9_a+BV@<3_&X_M4czifpQ<**IIfI;24T%Xfx3>!>U(ilOH2Z%bya`Ti&pnhH~HXfsQ&uD;7zt`7Y`jzPzh7|CW{MPd9#W3R z$H&L8C1j1~!D;O5bTVhO``oQOu&>Z`D98@nP9*V4ETvnRo z&tCsVfal9ExQDQN?>zUMjBIjyd%GQHPMTAbO2&q$EDkybkB0JzyT9{V8t7|#)_-nZ z@?dH<|W05Z&RG=9Tvg*QoS*rvtO-QMJmsPVHg#?neClQoRjY8ksW@(m+ zLNq7GLYJ@o4=Wl1@w2A!x!V?wH+5H#1UWr=6jM(R%?iPzpp(jAyJFoKLdMC zPsc0R+SZ#|9oVXDzkKjNYfQMMcH@q=w!q_aD7JPW8RzKcw`z@ZVkJnW)#L~FF1n2& ztG-af3ah9QqZ}?e39nL9neg+oO1U=D*ZIn?pCg*f#+w3~D#M-qDl>HAL7i5kh5Da4 zT6aFV7@#0D)ZEi#vVyj1RFD=$5?Tw@{Fg3Dk7Gy1W=08*6Wu*Wwj)1Il>YQ~b{c z5#u$F=AZLhVBu2(?kXepUsd3kw>i~V6) zQ@4$Y_dsl#!*1~K40Lsg`kz*M!N^pQC{*{!-cp=YY47yovkkzYzP`SdZk5U7lRTHj zo;uGha@(=eYRAbBkLEvK9SKtL8rOSmO-Yg#8#jd4IZih=cy3L(E)9g8%}kx2`_*7$ zw;w=`(MlqEV!XVA-QB43hb+4MRt5$WpK=xHCA^w#XN-M(e9X)kUxZr2Oga{OQ#$Br z)bjH3TJuP7kHb;8n++ZtX*I8nWZ*9~h#2YpwgD_rOBbe8)6y-_;YJKTftv34 z{YbTLZEL$YKcA>_;FN#M0RCEH60ljjl#`pA8oKb~hp@wh5Cg+Yi_U00_i6y)rr9JH ze)Ok@w)LlrsI2lE%zumuITm{~2aP9&HhtPJG;4dBeN#wihgcE6H;WJ}5GO77t zNX>)I$#2J<0h>~0GtGg9RrbUPq@K~vse*!ndWLA6kpNJ}ZXl^*5?|b7LVv4v;=M1c zBOxJCimp%rOXS#oc_-7qex0o0uZESdjPq1aKLKFjKETNfD{r=dJr*~pspK5jxO?ym4MDM$M1)2)# zT15so5mze7Tr%X`_PFg!1V@{ba&DPou2_SuQLUoNZr(M-&BAp~(~UU7Rc5m_AAry+ zHmYM1J32Ztsj$NL0N=D5CB@WX5iFoHhS~e`K&q?$ z^uoV->=W|fRVEkG#vlud07plCu47UHdDOpF&oo~tW&ke@WVRJV`Xmy&j}3*hfXu=| zPWwfsui@f;@H-JGAS5JIl-=1Il%`fo$Fb+si|2I)T5$lBIdzLmRoY`JD)t64#m8BM zae$EQ!VJDH$e{%4`B@y9nVGNlvaVi6>Iu}b6RCiZ@Xh)8ARHl%n(*cR-d>B$vf-yr z$LbT6Hi91Odb#Xwb?$4d$>^yDUqwa5iu}hHr~I%|TjxY(CZ>;3)Vk44`kHB@Y+w}H zBG=6kp@hD^qcD@{IrY}K;THUoRV|I-8UoI+FEcejKtTMAx9MC!zyXhU5WhtMp!}zXW<83@yus}8Q);%sTn|cN^FC``A z^=s?<_cIuPEOHd;S4Sd|U*6plcU#^zQRJ5Uz5Zkr>p5i}C~{Y+(8`PqnjQW?DA(l4 z$%!5rOTe2TYDQe8s*WT-BA43Q+TCedF8NIkDH|;M0w@+lR9u|e5Vjz04&zIE zY}am0T%}^pMMJ~DZBXmNl0bMCj6i$MtxvqSYes`*bIh{3SY{r@rKX12<53Q^1Yzen zcz{r#o%WVSpRQO&JwzVeuwo3|8x9GoA9nn zc=27a{WXOo(je-+x)n>maISL`Xn}%_nh9MV7XbVNrp2(^Ror`w#?fybl+29%hhGa z$yM+>;=o+Q7U(Cjc^SNw?^&`YUa+Yo2dbZtT$ zEthe3Mh9@dAzbhILeDqSZ`k?yvu-bTAT*LvFf_?^&qFTVW5bxS^77R1a+Wz=uwoP? z5LbUL>HArSR_sHFWT+(Ma)$U=G+xoUUN(`*;t8t@mUaFDOz?!1Pq5&>c+VHS*>~)z zRkJsY5~*J8)UbCLc>}hS{eHMIoRm~{D7B}WyS;t2vu782K*K+{Dkm2tZ6f6Q`Bk+u zZ(1zg%hwCU7M%(flTWh`Do%z2L@PgacH*h{Xlf3BjPh5{`2O)jHrA1kw|AutN$|eB zK&T$1^pe@IWfX1nV`0;FVuY|RGMe_=9Q(H_-rFp0xC0iI>Y2B&u%&y28N8s0IFECz z4_1rAP+NHOuJu&H>trJ{2_HV_oViU2<+UV95L4$PyIIvwt%2T9Sw$t}gb6l;f6lN} z{jP-xc3tumU!DTju$p^ih!KieKW>dDpt*hIlz47)ZS5&$2HEzZqJl@N=#H94H{xYw zVH5~{Jll4qWov-Iz(}t@nz|}KC1y6h-CQA$(eiYLxc#=dGdwenIio37%&gUU-9!^9 zx#=+7c#z0`^``-I&|2A(3%gE%k-oF_wm=Nu5%oWwuH0j4x&CKNf#JrIwyS=jsY%yH#$2fJe0$BUkXJ|CI zgyKOBt-q=bS3FvK_)+u7+uTwSD>gm7lQK@aTa``DMCg0Oydo-3&AQwd;X}nny&Wp> z#UMcv#7y6~oBXGch=7Id()EnY*1Qn7rtK{WfKjRUwAN@3GqM<_E>`o^nZ)Cb%MK7; z?cgwKJ$wJ~lb?*T{o4*>K>v~QN_~-Ng8=)4{7QX24sfnwlUB9kM$>s7SzUWi3`j1@ znTX-iod}HPF1`<8V!D)a{7#gYwT206p3!U8QUHrP+uv$!ohXw^Rzbd9=~P-KWg=Px z@+&NS_3_b?^gdqOCdx1*jySf~yH0;;>nLDjef?Ts8*_bwq+Vk2bnM)!K~zU=h%pRq z>fy|yp(mmei9nY8h6fcEPzzeb_x#vQR;|Q1Gx)jn;efbY94iz{*yeLPpj17qg)+b) z5GspjeFLN{tV*DDw?l#jS`BF3@Zt&&H{2P5Hd_j_s7ssbQ^LH4YQC#UKvix-_STWHC0219_pb?Y@ zH_bL9iOw5*XBlM?O1_iD_)a7g0{8Nm7`#?YPQDQ`h-0MFHg__0K?9W#|CsW8(YPC% zLUl7Ngf$MNjO+Fr?Y#QnFEQrXsDwrS2>>O?D`DG_HJg=!#RCuXe|81HWbe>UvrSD(sDeme#rTo5G+Z9Mx2x(NXF^3U&-SWHI?MFq};<3awvgY6X@DN6pI z;AkO-3jC9@zfu2x^yVKRM8c6o9^gMH%79ac{y#PV(fI#y;mla#mSW470^LDAe&56O zBE#y-%d@S|bOHc}cRSiNve_VcNz=H3@%Q=15;Y(n+*UpV>>-X>k$_6*4bZcinVB_R zo)%ON=LQD{a{=Vv;0$`>nbYZCKSYHWlhOPZA4^?~jb9`r3~x@>g^d17&0EU@0N$F+ zZD_796>xd}-tMcW>&foo+0ho>g%Lzg;=B1> zZ1fq%v`DVl(RHAkw6U=PT2%k-nZTWFYJfODqweVFn0xW^)vJZEGKVEa!`%&ho?CdAVQS+={HcQHX zyB)wIOl)k=&F|w6T`Yixb(>Q1rwWsph`8pmJj6&(Pw$3 znwq9U+>?QUfm;nnbZe2;GVl1xv*thy1x^-Z{lc6JK$#08rIy))EACEA(b()OqE1%eA1xdQR2TgdfNyHZLLy^Mtrk9X-e6}(sjDjt#Q4z-lEK}F0BImGk(6}c zg=B;bk8yq1s;i63m}TnYaBSY;1ed>!HV4xjA4Zppzn|ZBcrFdFab#o%znG`^RAr@* z{R^$=(9r7uuPBY$nymA5bF2JBdL1C6zOryrzY&q#C%!mc_4N{?W`KM*FfafJR~@c# z?@Dh>mYM|>6ma7Ceh=w0Ki;0bF*9{}arP`Egfi(uNW4a?g=DnI?;jqJ-#3qx|Iw4g zS#rOYsW>s1a>~Zj)3Zv+_=6iv%(Xx5X1a)zF~FT?W=szSuhWqd5uuG9JtLrv%$F+% z=%AOk_w1L*hzMU7IKyH8n;AO40zexC1jL{xPc-#PO#?see+R0?>FFr|9Z<3JxsHes z{)&nUKo2^pTnQk?7eg91pQaxSug@r8YS2k#OZ?;6)4g1V!)m=X2nI%Pnd0pkMmej_ z6=lw8@?V&xqsY5y=bY_dD6Ov?&r>2*T@ z#03JWnDi*rD0g>GTG=qjml(AWM^lmlz!Yg z+vdH?J1phU5&quyXp`iZE}weq=Hd5R!`-m5Ukd(?_G_3WInVuNg}qEaii*f5xGTcV7VC{+xe${QBtsW`@8E#>D*Ec12a^Vy%QQQ}j_&D=T2JC+TFm-s<-l({y8^2*`4|XN@85L0=f~mcMYmE8YGu zs|C}vnVmJlBBWz1q4+t65{1ufO+%TC^^TeAB%EjV4>zW}>uj8U51&eRu`%D@J^f}@ z2337QBW^cpElVPxD(|kTiB}I0*A2_0tw!;aVT~pwrDFtQfj2vQ5Oy&?C-w0|ux^E7 zjM7-PT04wFTVwq_VYXzocYU#-gPUfu1phuKtM!=BZRf>uK`xRhr;OXu@S!N-< zD(>dh(%VaIh-J^is`@;fl$2KUYNL9E+W

fI^+XlQaEgF1daWk@RvE8e3Wzff*PN z#|K86In|8U))=Zg=O-#D+=l6KkFMV;ceQ4%E2ufP3c@l5cJr4 zXn#Nc9duIamp!&(n_VrEykWjE^tHZSWdY_B3buR0Jsj;g$S62^7RG(9l2)h~f9{v)@lkLMO0Aly-}x zi#sDgnBA}hU?5xA>H-6_`{KKA;R{o{VHTqm)>)gA%+BKR0f%Q0YiOQK`|qe`V4im_ zGSCQl=BchC{*cdsLbqswh;&5zGWTT-4dqFAOiY$DL9j2N|2~XufC5^)0Vy2rv;R

UPDq+rKvd=jnw8-=lA(W^89ko`Wwi`qMBgZHA-Y8;CyYOXfAveQ*2zY2GY?bqr?A|fK^B!-GX>nubn%}3Mp zKvMbxxfzGbe|^Q^fd)GMdpA&^O6n)kBeWzvjT@z<6oP^pn@1Zgfz~Jf!mYMNa$9D;So`zt7nLfP_N{b)` ziFuoWx9&uwXd_U$k YBGbC7D^hX_9A5&VZmY`|%bGs<{9 literal 0 HcmV?d00001 From 79ada8d3c11cede26cfd3745fb6612d5343dead8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Sat, 14 Dec 2024 13:31:33 +0100 Subject: [PATCH 2/7] Style check and grammar review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- .../Async-Service/Async-Service-Main.rst | 259 ++++++++++-------- 1 file changed, 144 insertions(+), 115 deletions(-) diff --git a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst index 577f1d84eec..0a1bcd72c5f 100644 --- a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst +++ b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst @@ -22,9 +22,10 @@ Background For information on how to write a basic client/server service see :doc:`checkout this tutorial <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>`. -**All** service clients in ROS2 are **asyncronous**, in this tutorial an example of service client is -studied to provide some insight of that fact while explaining the reason for being asyncronous and some -consequences about timing. +**All** service **clients** in ROS2 are **asynchronous**. In this tutorial, an example +of a service client is analyzed to provide insight into this fact, explaining +the reasons for its asynchronous nature and some of the timing-related +consequences. Consider the following diagram: @@ -32,39 +33,42 @@ Consider the following diagram: :target: images/sync-client-diagram.png :alt: A sequence diagram that show how a sync-client waits for the response -It shows an syncronous client, the client makes a request and waits for the response, that is, -its thread is not running, it is stopped until the response is returned. +It shows a **synchronous** client. The client makes a request and waits for +the response, meaning its thread is not running but blocked until the +response is returned. -On the other hand, in the following diagram an asyncronous ROS2 client is showed: +In contrast, the following diagram illustrates an asynchronous ROS2 client: .. In the definition diagram there is an invisible interaction, in white color, otherwise the activation bar could not be deactivated. - .. image:: images/async-client-diagram.png :target: images/async-client-diagram.png :alt: A sequence diagram that show how a async-client is not waiting but doing something else -In general, an asyncronous client is running after making the request, of course, it could -be stopped by invoking a waiting function or at any other blocking function, but this -diagram shows a ROS2 client, and, in ROS2 in order to get the response, the thread has to -be spinning, that is: it has to be waiting for any incoming events (topics, timers...) -including the response event. This fact is showed in the diagram: when the ``Event A`` is received, -its callback is executed (the client is *activated*) and, afterwards, the response is -received and the client executes the callback for the response. +In general, an asynchronous client continues running after making the request. +Of course, it could be stopped by invoking a waiting function or another +blocking function, but this diagram shows a ROS2 client, and in ROS2, to receive +the response, the thread must be spinning, meaning it has to poll for incoming +events (topics, timers, etc.), including the response event. This behavior is +depicted in the diagram: when ``Event A`` is received, its callback is executed +(the client is *activated*), and afterward, the response is received, and the +client executes the callback for the response. -Since any service client in ROS2 needs to be spinning to receive the response for the -server. That means that **all clients in ROS2 are asyncronous** by design (they can not be -*just waiting*, they can wait while spinning). +Since any service client in ROS2 needs to be spinning to receive the server's +response, all clients in ROS2 are asynchronous by design (they cannot simply +wait; they can only wait while spinning). -Thus, if a node **is** already **spinning** and has requested a service -**inside** a callback (any callback), the best approach is just let the callback finish, -you can process the response later in another callback in the future. You might find that -this approach is not obvious because the code to be executed after receiving the response -is not write inmediately after making the request, but you will get use to it, it -is just to write or look for that piece of code somewhere else. +Thus, if a node is already spinning and has requested a service inside a +callback (any callback), the best approach is to let the callback finish. +You can process the response later in another callback in the future. This +approach might seem unintuitive because the code to be executed after +receiving the response is not written immediately after making the request. +However, you will get used to it; you just need to write or locate that +piece of code elsewhere. -This tutorial shows how to write an asyncronous client that works like in the diagram. +This tutorial demonstrates how to write an asynchronous client that +operates as shown in the diagram. Prerequisites ------------- @@ -184,17 +188,18 @@ And build as usual: 1.2 Examine the server code ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -.. Note:: +.. warning:: - This package is NOT a real service server example, but an - instrument to experiment and understand the consecuences of - timing in services. It includes an artificial and **unnecessary** - delay in responding the requests. Nevertheless, it could be - used as an example if you remove the delay. + This package is NOT a real service server example but rather an + instrument to experiment with and understand the consequences of + timing in services. It includes an artificial and unnecessary + delay in responding to requests. Nevertheless, it could + serve as an example if the delay is removed. -Actually, there is no relevant items here. Only note that the -callback that attends the request is slept for a given amount of -seconds. The rest of the node is quite standard. +Actually, there are no particularly relevant elements here. The main +point to note is that the callback handling the request is intentionally +delayed for a specified number of seconds. The rest of the node follows +a standard implementation. 2 Creating the client package ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -355,28 +360,30 @@ the request is made here, **inside** this callback: } } -This callback check the topic value and, if greater or equals to zero, prepare a request to -the service using the new topic value and `100` as arguments, and make the request itself. +This callback checks the topic value and, if it is greater than or equal to +zero, prepares a request to the service using the new topic value and 100 as +arguments, and then sends the request. -The important items about ``async_send_request`` are: +Key points about ``async_send_request`` are: -* It is called inside a callback, that is, it is executed in the thread that +* It is called inside a callback, meaning it is executed in the thread that is spinning the node. -* It is not blocking, that is, it will return almost inmediately. So it will - not block the execution of the thread. +* It is non-blocking, meaning it returns almost immediately without stopping + the execution of the thread. -* It provides a callback as an argument, ``AsyncReceiveCallbackClient::handle_service_response``, - that is where the code will *jump* when the response is received. +* It accepts a callback as an argument, ``handle_service_response``, which is + where the code will *jump* when the response is received. -* There is **not** any other sentence after it in ``topic_callback``, so the - execution will leave this callback and return to the spinning method. +* There are no additional statements after the call to ``async_send_request`` + in ``topic_callback``, so execution will exit this callback and return + to the spinning method. -* Just remember, in order to receive the response the node should be spinning. +* Keep in mind that the node must be spinning to receive the server response. -* The ``future_result`` object could be ignored because it will be received - at ``handle_service_response``, but you might use it to track the - *state* of the request if necessary. +* The ``future_result`` object can be ignored since the response will be + handled in ``handle_service_response`` using the argument. However, it can + also be used to track the *state* of the request if necessary. The second callback is for receiving the server response. Note that, being a callback, it will be executed at the spinning thread. The code is @@ -396,15 +403,16 @@ quite simple: publisher_->publish(result_msg); } -The response is given in the parameter, `future`, it is obtained in the first -line and logged. Then, the response could be processed as required, here, just -as an example, it is published in a topic. +The response is provided in the parameter future. It is retrieved in the first +line and logged. Afterward, the response can be processed as needed. In this +example, it is simply published to a topic. .. note:: - - Compare to the code of an hypotethical alternative syncronous client the difference is where the code - to be executed *after* getting the result is written. In a syncronous call it is right *after* - the sentence calling the request, while in an asyncronous request it is at **another callback**. + Compared to the code of a hypothetical synchronous client, the key + difference lies in where the code to be executed *after* obtaining + the result is placed. In a synchronous call, it is written directly + *after* the line that makes the request. In an asynchronous call, however, + it is located in **another callback**. Installing the examples directly --------------------------------- @@ -421,9 +429,9 @@ you can install them using apt for your ROS 2 distro: Study how client and server interact ------------------------------------ -Whatever you write the package or install directly the example, this section -provides some cases of study to show how client and serve interact with each -other and the impact of time execution in that interaction. +Whether you write the package yourself or directly install the example, this +section provides cases of study to illustrate how the client and server +interact and the impact of execution timing on their interaction. Discover available components ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -444,7 +452,7 @@ should get: examples_rclcpp_async_recv_cb_client examples_rclcpp_delayed_service -Just remember to source the workspace if you don't. +Just remember to source the workspace if you haven't already. Run the delayed server ^^^^^^^^^^^^^^^^^^^^^^ @@ -461,16 +469,16 @@ The service will start, in another terminal run: ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 2, b: 5}" -After a short delay you will get the response, return to the terminal -where you launch the server, you will have there two INFO log messages -showing the time at the incoming request and the time when the response +After a short delay, you will receive the response. Return to the terminal +where you launched the server, and you will see two INFO log messages +indicating the time of the incoming request and the time when the response was sent. .. note:: - As already said, this server is designed NOT to be an example, but an - emulator of a service that will take a significant amount of time to - compute the response. + As mentioned earlier, this server is designed NOT to serve as a standard + example but as an emulator of a service that requires a significant + amount of time to compute a response. You might fine tune the timing by running: @@ -478,8 +486,8 @@ You might fine tune the timing by running: ros2 param set /delayed_service response_delay 2.5 -Being 2.5 the new delay in seconds. Kept that value as the delay to have -plenty of time to run next steps. +With 2.5 as the new delay in seconds, keep this value to ensure sufficient +time for the subsequent steps. Run the asyncronous client ^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -490,41 +498,41 @@ Start a new terminal and run (source the workspace, if you have to): ros2 ros2 run examples_rclcpp_async_recv_cb_client client_main -This node doesn't make a request on launching, instead the call for service -is done when a topic is received, that is, the call to `async_send_request` -is **inside** a ros2 callback. So you have to trigger the request by publishing -to a topic, start a third terminal and run: +This node does not make a request upon launch. Instead, the service call +is made when a topic is received. That is, the call to `async_send_request` +is **inside** a ROS2 callback. To trigger the request, you need to publish +to a topic. Open a third terminal and run: .. code-block:: bash ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 5" -Check the messages in both terminals, the one for the server and the one -for the client. You will find that, as you did manually before, the client made -a request and a bit later it received the response. On the server side -you will see exactly the same messages, no news there. +Check the messages in both terminals: one for the server and one +for the client. You will observe that, as before, the client made a request +and received the response shortly afterward. On the server side, +you will see the same messages, confirming the interaction. -Now, Why is this client asyncronous? Being asyncronous means that the -program is not stopped waiting for a result, insteads it keeps running -doing other things while waiting for the response. Actually, this is -the case of **all** ROS2 service clients because they all have to keep -spinning to keep the incoming response from the rclcpp layer. +Now, why is this client asynchronous? Being asynchronous means that the +program does not stop and wait for a result. Instead, it continues running +and performing other tasks while waiting for the response. This is +true for **all** ROS2 service clients because they must keep +spinning to handle incoming responses from the `rclcpp` layer. .. note:: - In this example, the client is the part that is asyncronous. Applying the - term asyncronous to the server doesn't make any sense in this example. + In this example, the client is the asynchronous node. Applying the + term asynchronous to the server in this context does not make sense. -Let's try to see it in action, just run these commands one after the -other (if you are not fast enough, just set the delay time to a higher -value), copy-paste them to your terminal will also work: +Let's see this in action. Run the following commands one after the +other. If you're not fast enough, you can increase the delay time to a +higher value. Copy-pasting the commands into your terminal will also work: .. code-block:: bash ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 10" ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 15" -Check the client terminal, you will get something similar to: +Check the client terminal; you should see output similar to the following: .. code-block:: text @@ -542,7 +550,15 @@ later. That is, two request were done in a row before getting the results and later they were also received one after the other. But, why the second response takes more that 2.5 seconds? -Check now the terminal that runs the server, you will see something similar to: +Since the client **is** asynchronous, it keeps spinning and continues to +receive topic messages. In the previous logs, the topics for 10 and 15 were +received at times ending in 16 and 18 seconds, respectively, and the responses +were received later. This means two requests were made in quick succession +before their results were received, and the responses were processed later. +But why does the second response take more than 2.5 seconds? + +Now check the terminal running the server; you should see output similar +to the following: .. code-block:: text @@ -555,45 +571,58 @@ The server logs a message in its service callback, the client made the second call at a time whose seconds are 18.45, but the message here is logged at 19.40, what happens? -Actually, it is very simple, the server is spinning, just like any other node -and this server only has one thread, so the first callback, the one with -arguments 10+100 **blocks** the spinning thread until it completes and returns. -Then the spinning takes control again, looks for another incoming request and -calls again the callback method with the new arguments: 15+100. Even if we -might think on them as parallel requests, that is not true, if a -**Single-Threaded Executor** is used, only one thread is used and, thus, the -callback are executed strictly in sequence. - -The key concept here is that an asyncronous call, like in the client, -does not **block** execution, so the spinning in the client gets the control again after processing the -callback with the request inside, that way it can execute the callback for other incoming -messages, including other topic messages **and** the incoming responses. -The client node is also run by a Single-Threaded Executor, so, callbacks are -also processed in sequence. The difference is that the callbacks in the client -return almost inmediately and so, apparently, the client is always ready. - -Another lesson here is that you should make service requests with caution, if you -make requests at a high frequency you should be aware of the efficiency of your server to -produce the responses. +The server logs a message in its service callback. The client made the second +call at a time ending in 18.45 seconds, but the server logs the corresponding +message at 19.40 seconds. What happens here? + +It is actually quite simple. The server is spinning, just like any other node, +and this server only has one thread. Therefore, the first callback, which +processes the request with arguments 10+100, **blocks** the spinning thread +until it completes and returns. Once it finishes, the spinning resumes, +processes the next incoming request, and calls the callback method with the +new arguments: 15+100. While it might seem like the requests are handled in +parallel, that is not the case. When a **Single-Threaded Executor** is used, +only one thread is available, and the callbacks are executed strictly in +sequence. + +The key concept here is that an asynchronous call, like in the client, +does not **block** execution. As a result, after processing the callback +containing the request, the client regains control and continues spinning. +This allows it to execute callbacks for other incoming messages, including +topic messages **and** incoming responses. + +The client node also uses a **Single-Threaded Executor**, so callbacks +are processed sequentially. However, the difference is that callbacks in +the client return almost immediately. This gives the appearance that the +client is always ready to process new events. + +Another important lesson is that service requests should be made with caution. +If you make requests at a high frequency, you must consider the server's +efficiency in generating responses to avoid overwhelming it. .. note:: - Actually, in any circumstance, it is a good idea to check callback execution - times, since they **block** spinning and could produce unexpected and - unwanted side-effects. + In any circumstance, it is advisable to monitor callback execution times, + as they **block** spinning and can lead to unexpected and undesirable + side effects. Just as a final note: programming a service server that takes too long in computing the response is a potential issue in your system, this inconvenience is a reason for using actions (among others). +As a final note, designing a service server that takes too long to +compute a response can become a significant issue in your system. This +limitation is one of the reasons why using actions is often preferred +in such cases. + Summary -------- -You have create an asyncronous client node using a design that could be -used in combination with other events in ROS2: topics, timer, etc. Its -execution model is quite simple since the node is just executed in the +You have created an **asynchronous** client node using a design that +can be integrated with other ROS2 events, such as topics, timers, etc. Its +execution model is straightforward, as the node operates in the default mode (single-threaded). -You have made some experiments about timing and the impact of -blocking callbacks and you should now understand better the meaning -of asyncronism and its impact in code design. +You have conducted experiments on timing and the effects of +blocking callbacks, which should help you better understand the +concept of **asynchronism** and its impact on code design. \ No newline at end of file From 08138320c74f04c9397b08cd92f0952bf4dbd18e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Sat, 14 Dec 2024 13:40:24 +0100 Subject: [PATCH 3/7] Fix links MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- .../Intermediate/Async-Service/Async-Service-Main.rst | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst index 0a1bcd72c5f..3e65d65e359 100644 --- a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst +++ b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst @@ -419,7 +419,7 @@ Installing the examples directly You might get the packages directly from code sources (clone the git repository in a workspace and colcon build them) or if you -are using Ubuntu and you follow the `installation instructions `, +are using Ubuntu and you follow the `installation instructions `, you can install them using apt for your ROS 2 distro: .. code-block:: bash @@ -436,7 +436,7 @@ interact and the impact of execution timing on their interaction. Discover available components ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -To see what packages that contains `examples_` are registered and available +To see what packages that contains *examples_* are registered and available in your workspace, execute the following command in a terminal: .. code-block:: bash @@ -444,7 +444,7 @@ in your workspace, execute the following command in a terminal: ros2 pkg list | grep examples_ The terminal will show a list of packages from ros2_examples, actually, -the list of packages whose name starts with `examples_`. At least you +the list of packages whose name starts with *examples_*. At least you should get: .. code-block:: text @@ -499,7 +499,7 @@ Start a new terminal and run (source the workspace, if you have to): ros2 ros2 run examples_rclcpp_async_recv_cb_client client_main This node does not make a request upon launch. Instead, the service call -is made when a topic is received. That is, the call to `async_send_request` +is made when a topic is received. That is, the call to ``async_send_request`` is **inside** a ROS2 callback. To trigger the request, you need to publish to a topic. Open a third terminal and run: From 6b89e65343b6db5902208e3cce64d775190a1b2d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Sat, 14 Dec 2024 13:52:13 +0100 Subject: [PATCH 4/7] Fix spelling and remove some paragraph after review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- .../Async-Service/Async-Service-Main.rst | 24 ++++--------------- 1 file changed, 5 insertions(+), 19 deletions(-) diff --git a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst index 3e65d65e359..5c84d802f0f 100644 --- a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst +++ b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst @@ -3,14 +3,14 @@ Async-Service Tutorials/Async-Service -Writing a service with an asyncronous client node +Writing a service with an asynchronous client node ================================================== .. contents:: Table of Contents :depth: 2 :local: -**Goal:** Understanding asyncronism in the context of services. +**Goal:** Understanding asynchronism in the context of services. **Tutorial level:** Intermediate @@ -408,6 +408,7 @@ line and logged. Afterward, the response can be processed as needed. In this example, it is simply published to a topic. .. note:: + Compared to the code of a hypothetical synchronous client, the key difference lies in where the code to be executed *after* obtaining the result is placed. In a synchronous call, it is written directly @@ -489,7 +490,7 @@ You might fine tune the timing by running: With 2.5 as the new delay in seconds, keep this value to ensure sufficient time for the subsequent steps. -Run the asyncronous client +Run the asynchronous client ^^^^^^^^^^^^^^^^^^^^^^^^^^ Start a new terminal and run (source the workspace, if you have to): @@ -543,13 +544,6 @@ Check the client terminal; you should see output similar to the following: [INFO] [1733332219.403816764] [examples_rclcpp_async_recv_cb_client]: Response: 110 [INFO] [1733332221.904430291] [examples_rclcpp_async_recv_cb_client]: Response: 115 -Since the client **is** asyncronous, it keeps spinning, and thus receiving -topic messages, in the previous logs the topics for 10 and 15 were received at -a time ending in 16 and 18 seconds respectively, and the responses were received -later. That is, two request were done in a row before getting the results and -later they were also received one after the other. But, why the second response -takes more that 2.5 seconds? - Since the client **is** asynchronous, it keeps spinning and continues to receive topic messages. In the previous logs, the topics for 10 and 15 were received at times ending in 16 and 18 seconds, respectively, and the responses @@ -567,10 +561,6 @@ to the following: [INFO] [1733332219.403700193] [delayed_service]: Request:15 + 100 delayed 2.5 seconds [INFO] [1733332221.903918827] [delayed_service]: Response: 115 -The server logs a message in its service callback, the client made the second -call at a time whose seconds are 18.45, but the message here is logged at 19.40, -what happens? - The server logs a message in its service callback. The client made the second call at a time ending in 18.45 seconds, but the server logs the corresponding message at 19.40 seconds. What happens here? @@ -606,10 +596,6 @@ efficiency in generating responses to avoid overwhelming it. as they **block** spinning and can lead to unexpected and undesirable side effects. -Just as a final note: programming a service server that takes too long in -computing the response is a potential issue in your system, this inconvenience -is a reason for using actions (among others). - As a final note, designing a service server that takes too long to compute a response can become a significant issue in your system. This limitation is one of the reasons why using actions is often preferred @@ -625,4 +611,4 @@ default mode (single-threaded). You have conducted experiments on timing and the effects of blocking callbacks, which should help you better understand the -concept of **asynchronism** and its impact on code design. \ No newline at end of file +concept of **asynchronism** and its impact on code design. From b7fe3e3eba1bc2b4cf649f30e5d9daf6daea87d9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Mon, 30 Dec 2024 14:06:53 +0100 Subject: [PATCH 5/7] Revision based on comments MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- .../Async-Service/Async-Service-Main.rst | 453 ++++++++---------- .../images/sync-client-diagram.plantuml | 2 +- 2 files changed, 202 insertions(+), 253 deletions(-) diff --git a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst index 5c84d802f0f..fa8effc7937 100644 --- a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst +++ b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst @@ -1,7 +1,4 @@ -.. redirect-from:: - - Async-Service - Tutorials/Async-Service +.. Tutorials/Intermediate/Async-Service Writing a service with an asynchronous client node ================================================== @@ -19,25 +16,30 @@ Writing a service with an asynchronous client node Background ---------- -For information on how to write a basic client/server service see -:doc:`checkout this tutorial <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>`. +For information on how to write a basic client/server service see :doc:`Writing a Simple Service and Client <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>`. + +In this tutorial we will create a service server with a artificial delay and a service client that makes requests to the service server **inside a callback**. +We will use both to understand the concept of asynchronism and to evaluate the impact of timing in the design of services. + +The delay in the server will make it easier to observe client activity; that activity is the difference between synchronous and asynchronous requests. + +A **synchronous** client is idle (i.e. **doing nothing**) after making a request. +Once it receives the response it resumes execution with the statement immediately following the request. -**All** service **clients** in ROS2 are **asynchronous**. In this tutorial, an example -of a service client is analyzed to provide insight into this fact, explaining -the reasons for its asynchronous nature and some of the timing-related -consequences. +Conversely, an **asynchronous** client can **continue running** after making the request, performing other tasks. +Later, it may either wait for the response or execute a predefined callback. +In this tutorial, the client will execute a callback when the response is received. -Consider the following diagram: +Consider the following diagram: .. image:: images/sync-client-diagram.png :target: images/sync-client-diagram.png :alt: A sequence diagram that show how a sync-client waits for the response -It shows a **synchronous** client. The client makes a request and waits for -the response, meaning its thread is not running but blocked until the -response is returned. +It shows a **synchronous** client. +The client makes a request and waits for the response, meaning its thread is blocked (i.e. not running) until the response is returned. -In contrast, the following diagram illustrates an asynchronous ROS2 client: +In contrast, the following diagram illustrates an asynchronous ROS 2 client: .. In the definition diagram there is an invisible interaction, in white color, otherwise the activation bar could not be deactivated. @@ -47,40 +49,34 @@ In contrast, the following diagram illustrates an asynchronous ROS2 client: In general, an asynchronous client continues running after making the request. -Of course, it could be stopped by invoking a waiting function or another -blocking function, but this diagram shows a ROS2 client, and in ROS2, to receive -the response, the thread must be spinning, meaning it has to poll for incoming -events (topics, timers, etc.), including the response event. This behavior is -depicted in the diagram: when ``Event A`` is received, its callback is executed -(the client is *activated*), and afterward, the response is received, and the -client executes the callback for the response. - -Since any service client in ROS2 needs to be spinning to receive the server's -response, all clients in ROS2 are asynchronous by design (they cannot simply -wait; they can only wait while spinning). - -Thus, if a node is already spinning and has requested a service inside a -callback (any callback), the best approach is to let the callback finish. -You can process the response later in another callback in the future. This -approach might seem unintuitive because the code to be executed after -receiving the response is not written immediately after making the request. -However, you will get used to it; you just need to write or locate that -piece of code elsewhere. - -This tutorial demonstrates how to write an asynchronous client that -operates as shown in the diagram. +Afterward, when the response is required to proceed, the thread could call a waiting function to stop until the response is received. +In a ROS 2 client, however, the thread must be spinning to receive the response. +This means it has to continuously poll for incoming events (topics, timers, etc.), including the response event. +This behavior is depicted in the diagram: when ``Event A`` is received, its callback is executed (the client is *activated*). +Later, the response is received, and the client executes the corresponding callback for the response. + +Since any service client in ROS 2 must be spinning to receive the server's response, all clients in ROS 2 are inherently asynchronous by design. +Service requests cannot block the thread, and although they cannot simply wait, they can wait while spinning. + +.. attention:: + + **All** service **clients** in ROS 2 are **asynchronous**. + +Thus, if a node is already spinning and has sent a request to a service inside a callback (any callback), the best approach is to allow the callback to finish. +You can write another callback to process the response, which will be executed at a later time in the future. +This approach might seem unintuitive because the code to be executed after receiving the response is not written immediately after the request is sent. +However, you will become accustomed to it; you simply need to write or locate that piece of code in a different place. + +This tutorial demonstrates how to write an asynchronous client that operates as shown in the diagram. Prerequisites ------------- -In beginner tutorials, you learned how to :doc:`create a workspace <../../Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace>` -and :doc:`create a package <../../Beginner-Client-Libraries/Creating-Your-First-ROS2-Package>`. +In beginner tutorials, you learned how to :doc:`create a workspace <../../Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace>` and :doc:`create a package <../../Beginner-Client-Libraries/Creating-Your-First-ROS2-Package>`. -In :doc:`Writing a Simple cpp Service and Client <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>` you -learned how to define a custom service that adds two ints, we will use that service again. +In :doc:`Writing a Simple cpp Service and Client <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>` you learned how to define a custom service that adds two ints, we will use that service again. -The source code in this tutorial is at `rclcpp examples `, -you might get the code there directly. +The source code for this tutorial is located at `rclcpp examples `. Tasks ------ @@ -99,8 +95,7 @@ Update ``package.xml`` as usual. 1.1 Write the service server node ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -Inside the ``examples_rclcpp_delayed_service/src`` directory, create a new file called ``main.cpp`` -and paste the following code within: +Inside the ``examples_rclcpp_delayed_service/src`` directory, create a new file called ``main.cpp`` and paste the following code within: .. code-block:: C++ @@ -159,9 +154,7 @@ and paste the following code within: } -Update ``CMakeLists.txt`` to build the executable: add the following -lines to it (after finding packages): - +Update ``CMakeLists.txt`` to build the executable: add the following lines to it (after finding packages): .. code-block:: console @@ -171,7 +164,7 @@ lines to it (after finding packages): install(TARGETS service_main DESTINATION lib/${PROJECT_NAME}) -Then install dependencies if you need: +Then install dependencies if you need: .. code-block:: bash @@ -186,20 +179,14 @@ And build as usual: 1.2 Examine the server code -~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~~~~~~~ -.. warning:: +This node has a standard implementation with nothing special. - This package is NOT a real service server example but rather an - instrument to experiment with and understand the consequences of - timing in services. It includes an artificial and unnecessary - delay in responding to requests. Nevertheless, it could - serve as an example if the delay is removed. +.. warning:: -Actually, there are no particularly relevant elements here. The main -point to note is that the callback handling the request is intentionally -delayed for a specified number of seconds. The rest of the node follows -a standard implementation. + This package is a service server with an arbitrary and artificial delay in responding to requests. + It should not used unless the delay is removed. 2 Creating the client package ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -214,8 +201,7 @@ Update ``package.xml`` as usual. 2.1 Write the service client node ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -Inside the ``examples_rclcpp_async_recv_cb_client/src`` directory, create a new file called ``main.cpp`` -and paste the following code within: +Inside the ``examples_rclcpp_async_recv_cb_client/src`` directory, create a new file called ``main.cpp`` and paste the following code within: .. code-block:: C++ @@ -225,80 +211,79 @@ and paste the following code within: class AsyncReceiveCallbackClient : public rclcpp::Node { - public: - AsyncReceiveCallbackClient() - : Node("examples_rclcpp_async_recv_cb_client") - { - // Create AddTwoInts client - client_ = this->create_client("add_two_ints"); - - // Wait until service is avaible - while (!client_->wait_for_service(std::chrono::seconds(1))) { - RCLCPP_ERROR(this->get_logger(), "Service is not available, trying again after 1 second"); + public: + AsyncReceiveCallbackClient() + : Node("examples_rclcpp_async_recv_cb_client") + { + // Create AddTwoInts client + client_ = this->create_client("add_two_ints"); + + // Wait until service is avaible + while (!client_->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_ERROR(this->get_logger(), "Service is not available, trying again after 1 second"); + } + + // Create a subcription to an input topic + subscription_ = this->create_subscription( + "input_topic", 10, + std::bind(&AsyncReceiveCallbackClient::topic_callback, this, std::placeholders::_1)); + + // Create a publisher for broadcasting the result + publisher_ = this->create_publisher("output_topic", 10); + + RCLCPP_INFO(this->get_logger(), "DelayedSumClient Initialized."); } - // Create a subcription to an input topic - subscription_ = this->create_subscription( - "input_topic", 10, - std::bind(&AsyncReceiveCallbackClient::topic_callback, this, std::placeholders::_1)); - - // Create a publisher for broadcasting the result - publisher_ = this->create_publisher("output_topic", 10); - - RCLCPP_INFO(this->get_logger(), "DelayedSumClient Initialized."); - } - - private: - void topic_callback(const std::shared_ptr msg) - { - RCLCPP_INFO(this->get_logger(), "Received %d at topic.", msg->data); - if (msg->data >= 0) { - RCLCPP_INFO(this->get_logger(), " Input topic is %d >= 0. Requesting sum...", msg->data); - - // Create request to sum msg->data + 100 - auto request = std::make_shared(); - request->a = msg->data; - request->b = 100; - - // Calls the service and bind the callback to receive response (not blocking!) - auto future_result = client_->async_send_request( - request, - std::bind( - &AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1)); - } else { - RCLCPP_INFO(this->get_logger(), " Input topic is %d < 0. No request is sent", msg->data); + private: + void topic_callback(const std::shared_ptr msg) + { + RCLCPP_INFO(this->get_logger(), "Received %d at topic.", msg->data); + if (msg->data >= 0) { + RCLCPP_INFO(this->get_logger(), " Input topic is %d >= 0. Requesting sum...", msg->data); + + // Create request to sum msg->data + 100 + auto request = std::make_shared(); + request->a = msg->data; + request->b = 100; + + // Calls the service and bind the callback to receive response (not blocking!) + auto future_result = client_->async_send_request( + request, + std::bind( + &AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1)); + } else { + RCLCPP_INFO(this->get_logger(), " Input topic is %d < 0. No request is sent", msg->data); + } } - } - - // Callback to receive response (call inside the spinning method like any other callback) - void handle_service_response( - rclcpp::Client::SharedFuture future) - { - auto response = future.get(); - RCLCPP_INFO(this->get_logger(), "Response: %ld", response->sum); - // Publish response at output topic - auto result_msg = std_msgs::msg::Int32(); - result_msg.data = response->sum; - publisher_->publish(result_msg); - } + // Callback to receive response (call inside the spinning method like any other callback) + void handle_service_response( + rclcpp::Client::SharedFuture future) + { + auto response = future.get(); + RCLCPP_INFO(this->get_logger(), "Response: %ld", response->sum); + + // Publish response at output topic + auto result_msg = std_msgs::msg::Int32(); + result_msg.data = response->sum; + publisher_->publish(result_msg); + } - rclcpp::Client::SharedPtr client_; - rclcpp::Subscription::SharedPtr subscription_; - rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Client::SharedPtr client_; + rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Publisher::SharedPtr publisher_; }; int main(int argc, char ** argv) { - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; } -Update ``CMakeLists.txt`` to build the executable: add the following -lines to it (after finding packages): +Update ``CMakeLists.txt`` to build the executable: add the following lines to it (after finding packages): .. code-block:: console @@ -324,7 +309,7 @@ The code in this node: client_ = this->create_client("add_two_ints"); -* Waits for the service server to be avaible at constructing the node object: +* Waits for the service server to be avaible at constructing the node object: .. code-block:: C++ @@ -334,8 +319,7 @@ The code in this node: * And creates a suscriber and a publisher (nothing interesting here). -The node implements two callbacks, first one is for the subcription: ``topic_callback``, -the request is made here, **inside** this callback: +The node implements two callbacks, first one is for the subcription: ``topic_callback``, the request is sent here, **inside** this callback: .. code-block:: C++ @@ -352,42 +336,36 @@ the request is made here, **inside** this callback: // Calls the service and bind the callback to receive response (not blocking!) auto future_result = client_->async_send_request( - request, - std::bind( - &AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1)); + request, + std::bind( + &AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1)); } else { RCLCPP_INFO(this->get_logger(), " Input topic is %d < 0. No request is sent", msg->data); } } -This callback checks the topic value and, if it is greater than or equal to -zero, prepares a request to the service using the new topic value and 100 as -arguments, and then sends the request. +This callback checks the topic value and, if it is greater than or equal to zero, prepares a request to the service using the new topic value and 100 as arguments, and then sends the request. Key points about ``async_send_request`` are: -* It is called inside a callback, meaning it is executed in the thread that - is spinning the node. +* It is called inside a callback, meaning it is executed in the thread that is spinning the node. -* It is non-blocking, meaning it returns almost immediately without stopping - the execution of the thread. +* It is non-blocking, meaning it returns almost immediately without stopping the execution of the thread. -* It accepts a callback as an argument, ``handle_service_response``, which is - where the code will *jump* when the response is received. +* It accepts a callback as an argument, ``handle_service_response``, which is where the code will *jump* when the response is received. -* There are no additional statements after the call to ``async_send_request`` - in ``topic_callback``, so execution will exit this callback and return - to the spinning method. +* There are no additional statements after the call to ``async_send_request`` in ``topic_callback``, so execution will exit this callback and return to the spinning method. * Keep in mind that the node must be spinning to receive the server response. -* The ``future_result`` object can be ignored since the response will be - handled in ``handle_service_response`` using the argument. However, it can - also be used to track the *state* of the request if necessary. +* The ``future_result`` object can be ignored since the response will be handled in ``handle_service_response`` using the argument. + However, it can also be used to track the *state* of the request if necessary. + +The callback ``handle_service_response`` is for receiving the server response. +Note that, as a callback, it will be promptly executed by the node's main thread when the response is received. +This behavior is similar to what occurs with subscriptions. -The second callback is for receiving the server response. Note that, -being a callback, it will be executed at the spinning thread. The code is -quite simple: +The code is quite simple: .. code-block:: C++ @@ -403,25 +381,20 @@ quite simple: publisher_->publish(result_msg); } -The response is provided in the parameter future. It is retrieved in the first -line and logged. Afterward, the response can be processed as needed. In this -example, it is simply published to a topic. +The response is provided in the parameter ``future``. +The actual information is retrieved in the first line and logged on the second line. +Subsequently, the response can be processed as required. +In this example, it is simply published to a topic. .. note:: - - Compared to the code of a hypothetical synchronous client, the key - difference lies in where the code to be executed *after* obtaining - the result is placed. In a synchronous call, it is written directly - *after* the line that makes the request. In an asynchronous call, however, - it is located in **another callback**. + + This is the code that is executed after receiving the response, and it is **not written** immediately **below** the statement that sends the request. + If the client were synchronous, it will be written directly **after** the statement that sends the request. Installing the examples directly --------------------------------- -You might get the packages directly from code sources (clone the git -repository in a workspace and colcon build them) or if you -are using Ubuntu and you follow the `installation instructions `, -you can install them using apt for your ROS 2 distro: +You might get the packages directly from code sources (clone the git repository in a workspace and colcon build them) or if you are using Ubuntu, and you follow the `installation instructions `, you can install them using apt for your ROS 2 distro: .. code-block:: bash @@ -430,23 +403,19 @@ you can install them using apt for your ROS 2 distro: Study how client and server interact ------------------------------------ -Whether you write the package yourself or directly install the example, this -section provides cases of study to illustrate how the client and server -interact and the impact of execution timing on their interaction. +Whether you write the package yourself or directly install the examples, this section provides cases of study to illustrate how the client and server interact and the impact of execution timing on their interaction. -Discover available components -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1 Discover available components +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -To see what packages that contains *examples_* are registered and available -in your workspace, execute the following command in a terminal: +To see what packages contain the term *examples_* are available in your workspace, execute the following command in a terminal: .. code-block:: bash ros2 pkg list | grep examples_ -The terminal will show a list of packages from ros2_examples, actually, -the list of packages whose name starts with *examples_*. At least you -should get: +The terminal will show a list of packages whose name starts with *examples_*. +At least you should get: .. code-block:: text @@ -455,8 +424,8 @@ should get: Just remember to source the workspace if you haven't already. -Run the delayed server -^^^^^^^^^^^^^^^^^^^^^^ +2 Run the delayed server +^^^^^^^^^^^^^^^^^^^^^^^^ Start a new terminal and run: @@ -470,16 +439,13 @@ The service will start, in another terminal run: ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 2, b: 5}" -After a short delay, you will receive the response. Return to the terminal -where you launched the server, and you will see two INFO log messages -indicating the time of the incoming request and the time when the response -was sent. +After a short delay, you will receive the response. +Return to the terminal where you launched the server, you will see two INFO log messages +indicating the time of the incoming request and the time when the response was sent. -.. note:: +.. warning:: - As mentioned earlier, this server is designed NOT to serve as a standard - example but as an emulator of a service that requires a significant - amount of time to compute a response. + This server is designed to emulate a service that requires a significant amount of time to compute a response. You might fine tune the timing by running: @@ -487,53 +453,53 @@ You might fine tune the timing by running: ros2 param set /delayed_service response_delay 2.5 -With 2.5 as the new delay in seconds, keep this value to ensure sufficient -time for the subsequent steps. +With 2.5 as the new delay in seconds, keep this value to ensure sufficient time for the subsequent steps. -Run the asynchronous client -^^^^^^^^^^^^^^^^^^^^^^^^^^ +3 Run the asynchronous client +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Start a new terminal and run (source the workspace, if you have to): .. code-block:: bash - ros2 ros2 run examples_rclcpp_async_recv_cb_client client_main + ros2 run examples_rclcpp_async_recv_cb_client client_main -This node does not make a request upon launch. Instead, the service call -is made when a topic is received. That is, the call to ``async_send_request`` -is **inside** a ROS2 callback. To trigger the request, you need to publish -to a topic. Open a third terminal and run: +This node does not make a request upon launch. +Instead, the service call is sent when a topic is received. +That is, the call to ``async_send_request`` is **inside** a ROS 2 callback. +You need to publish to a topic to trigger the request. +Open a third terminal and run: .. code-block:: bash ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 5" -Check the messages in both terminals: one for the server and one -for the client. You will observe that, as before, the client made a request -and received the response shortly afterward. On the server side, -you will see the same messages, confirming the interaction. +Check the messages in the terminals running the server and client. +You will observe that the client sent a request and received the response shortly afterward. +On the server side, you will see the matching messages, confirming the interaction. -Now, why is this client asynchronous? Being asynchronous means that the -program does not stop and wait for a result. Instead, it continues running -and performing other tasks while waiting for the response. This is -true for **all** ROS2 service clients because they must keep -spinning to handle incoming responses from the `rclcpp` layer. +Now, how can we confirm this client is asynchronous? +Being asynchronous means that the program does not stop and wait for a result. +Instead, it continues running and performing other tasks while waiting for the response. +This is true for **all** ROS 2 service clients because they must keep spinning to handle incoming responses from the *rclcpp* layer. .. note:: - In this example, the client is the asynchronous node. Applying the - term asynchronous to the server in this context does not make sense. + In this example, the client is the asynchronous node. + Applying the term asynchronous to the server in this context does not make sense. -Let's see this in action. Run the following commands one after the -other. If you're not fast enough, you can increase the delay time to a -higher value. Copy-pasting the commands into your terminal will also work: +Let's see these concepts in action. +Run the following commands one after the other. +If you're not fast enough, you can increase the delay time to a higher value. +You can also copy and paste the commands directly into your terminal: .. code-block:: bash ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 10" ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 15" -Check the client terminal; you should see output similar to the following: +Check the client terminal. +You should see output similar to the following: .. code-block:: text @@ -544,15 +510,13 @@ Check the client terminal; you should see output similar to the following: [INFO] [1733332219.403816764] [examples_rclcpp_async_recv_cb_client]: Response: 110 [INFO] [1733332221.904430291] [examples_rclcpp_async_recv_cb_client]: Response: 115 -Since the client **is** asynchronous, it keeps spinning and continues to -receive topic messages. In the previous logs, the topics for 10 and 15 were -received at times ending in 16 and 18 seconds, respectively, and the responses -were received later. This means two requests were made in quick succession -before their results were received, and the responses were processed later. +Since the client **is** asynchronous, it keeps spinning and continues to receive topic messages. +In the previous logs, the topics for values 10 and 15 were received at times ending in 16 and 18 seconds, respectively, and the responses were received later. +This means two requests were made in quick succession before their results were received, and the responses were processed later. But why does the second response take more than 2.5 seconds? -Now check the terminal running the server; you should see output similar -to the following: +Now check the terminal running the server. +You should see output similar to the following: .. code-block:: text @@ -561,54 +525,39 @@ to the following: [INFO] [1733332219.403700193] [delayed_service]: Request:15 + 100 delayed 2.5 seconds [INFO] [1733332221.903918827] [delayed_service]: Response: 115 -The server logs a message in its service callback. The client made the second -call at a time ending in 18.45 seconds, but the server logs the corresponding -message at 19.40 seconds. What happens here? - -It is actually quite simple. The server is spinning, just like any other node, -and this server only has one thread. Therefore, the first callback, which -processes the request with arguments 10+100, **blocks** the spinning thread -until it completes and returns. Once it finishes, the spinning resumes, -processes the next incoming request, and calls the callback method with the -new arguments: 15+100. While it might seem like the requests are handled in -parallel, that is not the case. When a **Single-Threaded Executor** is used, -only one thread is available, and the callbacks are executed strictly in -sequence. - -The key concept here is that an asynchronous call, like in the client, -does not **block** execution. As a result, after processing the callback -containing the request, the client regains control and continues spinning. -This allows it to execute callbacks for other incoming messages, including -topic messages **and** incoming responses. - -The client node also uses a **Single-Threaded Executor**, so callbacks -are processed sequentially. However, the difference is that callbacks in -the client return almost immediately. This gives the appearance that the -client is always ready to process new events. +The server logs two messages in its service callback: one message when the request is received and another when the response is sent. +The client sent the request with values ``15 + 100`` at a time ending in 18.45 seconds, but the server logs the matching message at 19.40 seconds. +What is happening here? + +Actually, it is quite simple. +The server is spinning, just like any other node, and this server only has one thread. +Therefore, the first callback, which processed the request with arguments ``10+100``, **blocked** the spinning thread until it completed and returned. +Once it finished, the spinning resumed, and processed the next incoming request by calling the callback with arguments: ``15+100``. +While it might seem like the requests are handled in parallel, that is not the case. +When a **Single-Threaded Executor** is used, only one thread is available, and the callbacks are executed strictly in sequence. + +The key concept here is that an asynchronous call, like in the client, does not **block** execution. +As a result, after processing the callback containing the request, the client node regains control and continues spinning. +This enables the client node to execute callbacks for other incoming messages, including topic messages **and** incoming responses. + +The client node also uses a **Single-Threaded Executor**, so callbacks are processed sequentially. +However, the difference is that callbacks in the client return almost immediately. +This gives the impression that the client is always ready to handle new events, as it should be. Another important lesson is that service requests should be made with caution. -If you make requests at a high frequency, you must consider the server's -efficiency in generating responses to avoid overwhelming it. +If requests are sent at a high frequency, the server's efficiency in generating responses must be considered to prevent it from being overwhelmed. .. note:: - In any circumstance, it is advisable to monitor callback execution times, - as they **block** spinning and can lead to unexpected and undesirable - side effects. + In any circumstance, it is advisable to monitor callback execution times, as they **block** spinning and can lead to unexpected and undesirable side effects. -As a final note, designing a service server that takes too long to -compute a response can become a significant issue in your system. This -limitation is one of the reasons why using actions is often preferred -in such cases. +As a final note, designing a service server that takes too long to compute a response can become a significant issue in your system. +This limitation is one of the reasons why using *actions* is often preferred in such cases. Summary -------- -You have created an **asynchronous** client node using a design that -can be integrated with other ROS2 events, such as topics, timers, etc. Its -execution model is straightforward, as the node operates in the -default mode (single-threaded). +You have created an **asynchronous** client node designed to integrate seamlessly with other ROS 2 events, such as topics, timers, and more. +Its execution model is straightforward, operating in the default single-threaded mode. -You have conducted experiments on timing and the effects of -blocking callbacks, which should help you better understand the -concept of **asynchronism** and its impact on code design. +Through experiments on the effects of blocking callbacks and timing, you should have gained valuable insight into the concept of **asynchronism** and its impact on code design. diff --git a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml index ba144d10d89..4d46658a78e 100644 --- a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml +++ b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml @@ -8,4 +8,4 @@ note left of Client : Wait for Response Server --> Client : Return Response deactivate Server -@enduml \ No newline at end of file +@enduml From 702533db37fa057ff821522d0da311f2cb96432f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Sun, 2 Feb 2025 16:42:54 +0100 Subject: [PATCH 6/7] Convert plantuml diagrams to mermaid MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- .../Async-Service/Async-Service-Main.rst | 42 +++++++++++++++---- 1 file changed, 35 insertions(+), 7 deletions(-) diff --git a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst index fa8effc7937..0a4107a78cd 100644 --- a/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst +++ b/source/Tutorials/Intermediate/Async-Service/Async-Service-Main.rst @@ -1,4 +1,3 @@ -.. Tutorials/Intermediate/Async-Service Writing a service with an asynchronous client node ================================================== @@ -32,9 +31,18 @@ In this tutorial, the client will execute a callback when the response is receiv Consider the following diagram: -.. image:: images/sync-client-diagram.png - :target: images/sync-client-diagram.png - :alt: A sequence diagram that show how a sync-client waits for the response +.. mermaid:: + + sequenceDiagram + participant Client + participant Server + + Client ->> Server : Send Sync Request + activate Server + Note left of Client: Waiting for Response + Server -->> Client : Return Response + deactivate Server + It shows a **synchronous** client. The client makes a request and waits for the response, meaning its thread is blocked (i.e. not running) until the response is returned. @@ -43,9 +51,29 @@ In contrast, the following diagram illustrates an asynchronous ROS 2 client: .. In the definition diagram there is an invisible interaction, in white color, otherwise the activation bar could not be deactivated. -.. image:: images/async-client-diagram.png - :target: images/async-client-diagram.png - :alt: A sequence diagram that show how a async-client is not waiting but doing something else +.. mermaid:: + + sequenceDiagram + + participant Other + participant Client + participant Server + + Client ->> Server : Send Async Request + Note left of Client: Client is spinning + activate Server + Note right of Server: Server is running the callback + Other ->> Client : Incoming Event A + activate Client + Note left of Client: Client is running Event A callback + deactivate Client + Note left of Client: Client is spinning + Server -->> Client : Return Response + deactivate Server + activate Client + Note left of Client: Client is running receive callback + deactivate Client + Note left of Client: Client is spinning In general, an asynchronous client continues running after making the request. From 6f9e76264a2fb30668b55780926bd313630c28b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Santiago=20Tapia-Fern=C3=A1ndez?= Date: Sun, 2 Feb 2025 16:44:15 +0100 Subject: [PATCH 7/7] remove plantuml files MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Santiago Tapia-Fernández --- .../images/async-client-diagram.plantuml | 20 ------------------ .../images/async-client-diagram.png | Bin 19672 -> 0 bytes .../images/sync-client-diagram.plantuml | 11 ---------- .../images/sync-client-diagram.png | Bin 9524 -> 0 bytes 4 files changed, 31 deletions(-) delete mode 100644 source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml delete mode 100644 source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.png delete mode 100644 source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml delete mode 100644 source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.png diff --git a/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml b/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml deleted file mode 100644 index 6d06e4574d4..00000000000 --- a/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.plantuml +++ /dev/null @@ -1,20 +0,0 @@ -@startuml -participant Client -participant Server - -Client -> Server : Make Async Request -note left of Client : Client is spinning -activate Server -note right of Server : Server is running the callback ---> Client : Incoming Event A -activate Client -deactivate Client -Server --> Client : Return Response -deactivate Server - -activate Client -note left of Client : Client is running receive callback -Client -[#white]> Client : -deactivate Client - -@enduml diff --git a/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.png b/source/Tutorials/Intermediate/Async-Service/images/async-client-diagram.png deleted file mode 100644 index 05bb58c1bfd7b0ad5dd46170de742f677eae565a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 19672 zcmeHvbzGEB-!7=IBC?19NQj7ngn-g5sFZ|sw=_t1ODPB_-QC??3j)&J-7MW5XV(5b z=XuZbp7`_p!Dp9ycjum&d*&P0b$#dK8xcN?Yk1d?kdQD0_+N@6AzgAoLPEB>dI?;S zx`}EDUMS38$(m~z8QU0WYMCSPX};4mRWsLodtcq=zK*%Mu^B53jj@5+J97&|18NN; zL(7g9BG81XuB5E_uj@$2pdIVTAn{g_OWZdqJ7vsgP@uTPD3i*Nc*YTae4Kfi+Pg>T zuT}ACh~FzbcpRo_mL?s4XVpMzT^4RJY$_4>+$cq?L2#37Tc+Z^ga8!<6C_>2e8QO7 zAbWVGn*YrFLMkf(Pm;eudCV4)!$STz^sU;L&RMK0Ou_UoPD;&s zKKjz&U4F3{i>?#HbHeT$&&=w&n8F!2pR6+`!mC=ubd8vJ<$8M+`e`z53r}5NK>|bL zW+(|}&W1kHyVCm!HcH{R)t{^|w8d7umT6FEG)#QZ;dD5-f@H*|1bvV!^r!xjwqYK_ z-{N!X6?g9H(QTpldad$R<96IYLK0jNc*!kkt-Kb6CM(r{d=ZB7wJ-4bjRs_Q{ukYa z1cK`pEpk0ny_ADOtqS25blOJOL{fDpB26E+61Q&!vk)^o-|Dy&@BE-+=S_#_#fsd; zzEOoI$~W%8iNzC}i6-rsz3i%i5xef=NQ)s)0#n4(-J~*pgAHDhrqYlgm%(c%Dl;y4 zv1Y7=ftT6>WGE_+*?ddU(vk@Y@7L@2jPixCVm^22rjPelTDUJ$n>RK3`Vg{+e`S$s z+MG^cdN-C?iHc-!h2XjyDXCW77n0%O;lZ!h@kZUyZUwobDynOcePmBr4&`!cu5USqodZ3`Ko@3H0+aBmxuk9*r6IDh7c8=aeea!ztDK^v1bI&aTLx5x4p4 z%k@^qyp8TjubobgSHieXa}5TwCDZJ`es~%{*7=4A=T$8X#eH^4qp9PGa%DKF`T6N1 z0RhkcJJC|Lu-FfXwu}kbwL2aV5vkD73rHIyyQwYA&$WB4yFmTt`bb0>f;`PfQ><&mKGozu1X!=$jV@J$=;) z3!;=svJwjm!x?TRWb@5bs*qAz3j>eA>nfNIpJ-Rz4SYQLfHm8GVyn%rxC9N23(BO0 zP8A+`42&%9)-$7;N4a%Q7j{cbllDxOtAo?iIei%i;gVdewhz|YzF`=Sm?sWZu?dgk z5GcN(CluO9A|N10779xe$?J+NHCP!Fj$*ajT^iclv^A^3s;o%*^unXHk}APc!KJrRhW9UTWJ$er(x+UzV|5D?XPDpor>JZOz(Hc3)sslg&? zyq${mYGc@#_VF{sY6*ubS6EVJ6__njOQ*={urkx_h=)DX1aoa7UL+DVVK}&+Ww3Hn zC_BiqKd0uL32ttWZD_VjP-!~v;dO_yyUo_tw&!+NV_=XODfK9;6*o6*Tl8gJy~>wp zq{FSId1~tHlYK%O9TG2RS8gn1u&}$$X$@6$lA@o^LM*)8lU^5QwAXQQgkG-7&MC4z3Nhqv z`)2&RbXumv`82s?mq$uAUUDIcc71s8=LtlH+l~wm+f3C?FW*KNhU6$$eUzT&bl^PN zZp9LR$tT)YObsJ)98zJ8S}t&B!-rB|Vul9uNlFrp)cFgt+zQDGuP|7-c#|*t^x$YG zBr!44)XFM`<0QpkeN~?^9;~?^i&z+lq>wX@9wPfB*hyw_%GYT7f#VMZVX z@zS=xjSRsFv}d&*D^2tD_1$&!rZX8%FVpBQHk^wvDo(&|2_$d5SLpbjcMcii`T()b z6Befq4>=wQvg2TNQ&GRuF5Z*z;5sXOKwp@ATp_SM>q}T6nR??f$Hy0o)QY9g6pF62 z5(-u1ft6`@kQ{KG-bv*u1m`yB*;~b>uDBhqJ1fH>?Tm&aVp;OWYaFfuiGm9eq0+1Z`&JN0mP!gO`D zS*_NWXJ*9HC3QtbMUSo8LYs%vAIYvy8IJA`rb$fJ*Vn^fYC8)`+sL^HGmz{GZ@*QQ z0A?=*P1CAEEP?dnN64=(JfK|3_w%D+cyQri!j1n0@^d$1G{LB#gsgdv4l~glc#~uO z-hqJxtdGdypO4vSMQ<1zbAu&?K7!F3ac|^GN@AqAw&61q(SfT!e=ZyibzA_me%sg8 z9pl%7Vji*w7M~xnJ*QN6z_PrLSeh=b?ck=)h*6_L8HtQ(k!~VP(?7qAMQF$l=?(qM zmOqu>$&o<2NnhNZFg^92oAZ{9NPnJoXSY#JR9xkCBm-oGcc7-8KG|S6cglYM)sKsM zJYUn>w9C15AWOmNSU2og%j@pLDdfx5rFI9|+s}}4QNVqpG+Tpx2-%ctaTzFVoBbcP zOux6^Y^ACBgr8Cwquy9DDN zLgiFnPN}M@s3tK|{-^g-&4dN-!%%pyKv97=jK%;H0DPtaa3@Ge&f1p=u7iKs@e!^4 z_04^hYM8n-Z9(maT3Bs$t)St5ejmW5h4Q1DwItZoip+X_sh>VwPn+wAVoTujyT|k{ zGBcR*i9)erp1ONJ{Uiaiv2%GxON%(E*FDSruZaQyj%Ry=o|r@w`s_*_kt}9A3&NV@ zNDC-X)G4g?2qr5Fi?iKc(Io!{ZyX7Mt(gYRqC%Ua`4Ai`*;uM}CSb6Oy}er(W1O;u zZgZIT(;rqloa`@k*N={Z1<8A`F)1T$>*eO@*%`qkDtFD<#>Exc`pR&sQiUZ=<>vc` zaoA7f3ymg~r>Aa_iF|EpB4ROpS*;n!cDO!Xks=Zm&p}VfWxaWyg@uKj{9{2$h3ULt zo_a&$r@OPWvk99jz+fsWj!jhAZH!m&(Ev+id$g@-RB(n#)#nQkV%4pFvSD@sj$oUbb{FaPGv z8)IYRdJha;?=s6Z`7}b7-elnnsSNCXGDtzTS=P*_PoH*ocJxOIb!BB`3$)r(KbNP9 zCwV7c`e8;on)zJH8{_46JEy^v#lS0w#VNlMqU5OFP0-kNkJ<9$X z$1~gPy@Ot`OM}=Cy7`DK*2lsKdy)7xKvWnz3odt8K=6ot;@*vybJ*>_J&_#w*uxvv z9}=6f-kXBi{EUoDd#cu@kDPFB*)JyiL69#VgI7PiC+T%GbUKmu5hC5(*0+M z-Mw24t0Sgd|ey8G|R98HxHlLA~iM=W@8D?dhQjE3?_cC-ZW=@++P-vG~tc|LApaF3*S_4yE)bb`GocvDn!Aa5LQ_nna_?YT*trR$L#KE1lQ& zbj}C0yK$%$tyi*2_+3`5dTeL?{QM5KxBW%9OlDppCYnNK1#ena)d*p{x)jnPF6O5u z9Z!5txp@;c%3PbB=5FrW&^$F5qAhc+xi~+$$6@Q{?*5ecDNA0b#a<~ez$GP2MqgJpIH)JM_#P2x2VvrJ|i`*T#B>fF%88H6DPPrGWw85r6%YcQ+9#sOiL zR!3x52A88=a7&VkTY$Oz2fBLG=&6Q(v>-$_9XJ~@QCKH3%*A3;K8?? zl6T`RMUEc`ac~Z%V3(z1wty=Md@S~!W2lYUYCW=`U?*Ft;+q1nznbo&B}OSc@YzYJ z4C$aJ3c;53ZT8oNA-!ApMwQ)p8ckdmrvbjr#><^a^H5TCb#)5K)aT-D{X|Y{BSpF= z(fSr3WP9=mVztyoOhMrl1Rl`$!GsSEfm?w1n0%X!^HIa z{P{C5O8%a=p~1^nP*9>+ExgNHa^$hGamU;y@H8Z9&P zPh{N<+Ys@IagO$NZ+24zw^@U^levQV4(hBcDJvJsd4t+s4&=wJxvSO`h?+1vt?$Bj;C9E z0@FyLxFF4|&jpqVOrPM%hPH1VjPc>qr(YP`$1AKR%gj=qL7YDVFHL)$5Lmh4f3kw~2{Ki};-uIOI9)_aHzau~B`r*wDqrMJV+S zSOm&d$CNph&-4eViZK@yf@4sgUqO7Y7KX}m6Sxdo!rk?8g{>3SYRw}#q?brg)O{2J zgWLSIt28d(n5wTG2G46F-#|v#Y-`h|8xKiIdnRP6wxnuHsJPIbuOd?Pyl)qi%`?B6 zMsgOL{!i~gtP(~=2m93o7@$=^+m*@uQ!1nfAkRLz1ZBKs-@09Z^Z^M(P3X)+LYq%o zJ1^b8WSqMecH@NTtAw{m6zjs=+~dXPME~+B+gJYx7i-q128U!%6c}4;Jhp^_!=`@q zX!J6Kt39^DVQ=L8k}hs2>aS53a~N;-UbifXQ#)}pl5@mH!g6*s#3VSSe^EZ#l}lLn ztE;kbxS(0(PX*_K^_JX2K>IS1q{oyZ}pI_GUOEwz0eIT(t z!COM+L|nHvjft4fU)vOj6Slj+gBBMR#U0^2k5&e<1Phn$tX{5aDy@Oej$Uf=SqFq`NNn7HRr{`YBAhF>=o zN?BM~uta0gFi`e)6M*@PUYw|iQBD)DJw)@f7iCIRD1nAU7d%Hwtw~$|+9aSeW~V&c zP0g!@dIGYAAdb2#y4P%JcaWtfmjCu+B4LeeX8Eygi?Q@kOTUBUnxx1ByRa130#U=1 zHEZ*>MZR99w3RnYQn4a@KKJfdCHf9YOHGS?pBaMJ(xR{R6=WX57%f z7L^_(pywMAngVvlBeiZ*+Tp?G<}{m~#_gf#(l+(}eoS=I{1&GPkvOehzlOXJ8`e;$ zqY6{aEAPhW=zBqw5Gv*PE!li6lx6dMD~&|fECs&ngd;K&R2c~@v{l>eok^Yi2u z;bB3*P@w!W5(ajC(BxG4BK3`ljnvjB^3V>}yjRt*AkXCNp;q9g78YeXZd^V31sm^^1eo1C-8Gub8la8XUny7PSxk4 zdja+01#gQA6Y%Ali`QO9MMd42BpU!v`S|1{_uvZH#Ku-M!DjNaJ8yq1z%f$cW#FKf zd*5b3)`1G;uyZX&vs5HVWssWR0{)-gOqzb2wIyHg=z5XsKkaJ5 zqAGS_gply)eGa{^m?Iv^iP_qi4@V#B&_#s>J&#c02-B5T^{sRu+v9Ix-RtcWCBvo( z!@KcDM5zO_$hH4bZRsBqKg~Aufp{{7vt71KZ{ZM4C0m*9WQDxGswyVtnT1<9l&h~% zDgWq%pI7z;J>y62|l&`l(W#P{L!cfryjh6b)a%o#s zo%I+gUB0QR_{+l$?bpI)-2QbZxwtl<6}h_nWs5IEyl)xjmi=~ez@_}lgw^#cgLi^`iStte{FPHq}tS9)Aql9 zpYg4+(U<4G7b~l|PDnri$pvioGQ!aUhxPFi3$D{Q!mZotL%E{ijAwS|4A&7KO$tA| zWlYOc7)w+@DRZ!>QjbV^z@U&JBrnnTHG-Wm>OpAY?Am^X;M0vKi9`kVdbmHL2QYLu z9pa0pt$x6!|M2zSf7IY77meoufD2v}DDMaCWgiG zN7G50(DS8)1AB)mPmGhnz%&xh^HRGay`VmeX!(~-_SKpzH-EH8{KHAUrcrTZne#-s z)!%P$Z*SSXJ)AIsxmaq$ra0k9L#um`79cFN6z=Amz#{^D+;FJ$Ifc#UW~jOS1^03E zT>nRb*0~4}7g}}8$z-p4k5+D;x{sS1!%g!m+ar5F0#nz#2;aU%p6ZsrdZ=@pENsH{ zXhX^DU_$H_L%U^1z(+5C!k~{T8cFY#Z{XIZ9G;~+LHX(pj=3mf6HOv&62jl6&TW3N z*hV%cu-_7YHvW|Lb$6*28+Mk+Jha-3$)_c0wBx;F+phZNl%GPefo`7c99J;n`EG(> z>2abfa6T&l%mAC`70WBV5s%o|T3|vj@CUZ`9nVXOE-vWwW9rFDmF=z(2so~;o}iTONaWEg7Ef~i@IfXmgw;Zi-^gQ^V5~@= zEnT3>+Pc&a|01ccRGBS2N)SpKRkJU@24b`IanX?Q7P`L4RzR#c#GM-<;fC>@{chk$Y@I$|(R9Gc9ODK{y&f&#vg%P`9-ErJjixTcH4ovW0S zMRuC!gqiPr%yJT$E$!+0SsX|Ox;b@C>l;z}7Gx4o3k^>W7TWO(OgSKacpT4JLmEj9 zzcP$=uLO=9%>_7hy?m{7`*Gh2CL#^kbGlqxI`kDL{<&UJG1BQ&_Zc~?x%uOOx{ZOT zec`a?==~$PLi-Sky|Fd6w3@7_gVUX)^)X?}F8KCmx2==%qbKt8$%K|5-t`XAVNc3@ z=Q*pIwh&Vyk;;B1OOT>Ct!hD74mfGiw8^$iw^KIR0){HPM=1SqHew}{$?cPR{kA4w zzd1@I`&u827t@xz9k}QDxr5b?PZ#$K<&u!<*5*-m!mX??2 zb{ZY6NoGh395?I(OY>?`)zYE|^~(hH5=-g3@o=*R-vDJ(`QAzy@my9fNSd$q*MQ0- zHadf$nr-vk(}Y<(hIG-Gr{TT6S}B=PN0UwaOIUZY_v06&c3xDSf6ps{Q;Po#tp-uL zR$EPH^k}oPe|=E9T)W3bM_QC7l z+cXBx_Yoy|7hIecZ1xySa}vtoVh3^zfwRKg@+c@__^Ve{nt9vV%>anBHer2v?iL5^wEPSE|q@Ot~XR z@nbljtpIW%S6xZNzz>-eAxg?ld#4S;^wuCdSZ8O`;GmuPuJ)^C)tjOj(!xv2Iy)R@ z(uD~LBqyxF50-e|yJnP@mHDTzWWmQNZ6ezycxSXZdN|ZJ0ys}r9c(9W-4rj<>-Rc4 z;hTp~RXbEjWiE*Z0g$vB7*RdN9Kv>yc^PgpR1}n!8p(kM_D_oc) z;neKL7)zeE60^$W6wDJTf)8uUyfT8JUoK3eb81e!jG66C|0}#w?)uhQ6>oJXO&5Po zR5+$4H)7r2b}|#EWFzsOfLw}WUu3Uud2b!ySHPq(n$X6_=9%`lZQZI?tkT*al<=^# zzG^|}ruDreND!`o*sQk~=VD*JJmEZy^ ztg49kkLSl)dvn2r^a-8d6RmXWAQ1viSiV4YHgR#qYP`00jEF^e&L)v)sZmUg4OSmt znUV7}{l0r#wDa3ux&Q*m8FBZ7-!b2R=l%Z_b;X^(1Go4U1^yFR_z~RvPU?R|Hh)19 ze^UGBgD`Y}UjoP~zi+WHMEY9AR}0 z>GRJ}aEZ0lW@q8-cuyi2n**S{3MKEPg0TtkoOE<_MDLQ5leY-E-)CpH2kdo=_}#x* z5hS2!_|cuuG>{lBr*l89^HP9V^6=C(2awJ8-{Z6o1t}B}k<)S?dDL1I9 zaqn<^?az>*QK_b)VR1O#T^lVK-g1Rt`UeE)vTtK#FVLob31`q338(*9o{aoD=+V+M z?>m%?T5Y&QL@_4^8TLot68wJ4?4mJbK6>nD+wlK6-h@`va)CysRusHt)T%fAf<0afnSw zEHwgBhX)Q-+L!@|J}qi$Y6?&|Y|PAxmDXY{&*%w(IwDf9KV5*vkAP)nb=7`7-|0vMX3Rt;SyXb)pvNmy>rHJfk3Q(^$; zs2qmc2}SJ2A9;hzDXTT$uvZTOR6AE085ud-qvsn0EARZTCHZO7J$tsKX=!Ph zUGybQA|-$O@X(r!j0{e)bTDCO1Q?N3*>zQm6mtM?tMT!D$C{ILMza>DWKhg}P|F6GFdQ8nf#FP=ZEF+Kdq_;IHmL&Q3R6JwlpWVkF^3kPQ&UqfcE+U4o}C<2 zl$Ymg+`se})U~}bg@TTqI}5Px08d{+Hr~buy{D6C()`)mJkmCc9Z_X|OgwDeV8gxc z*P(l|_vrh~B|BDCR-UsmFi}#z?u0FO#((s|X9@&`fk)btBncsO+cQNOgbVc z&}H6hv#Rl6pG2`)RofpuD=Pqaw=FbTO)-$zVVC3Ww;Omto}Nu$q)EqESXd85_E+@q z>=hLWe7IzsaKSRfr&V=6wpmqiJW6``@n%oKz*ms90B3KtHu5L~CHk&$?yrpW+Wge& zszFa&NQew@Q-UGX?dQpSf`WqW;S4I))9%kSTR!{gYG=Mn{0!x^+ov+5ma74bqN%xg zAe$fetd%tZJV8UxQyDNFEi1kF9{`^&5rMEJV13KV;-07nP0)fxdXIo$bzynD?=EJeDF$WeddOTh9Tc@Dq;SPyS~bzL0qq(fA! z;BB+Nvon$=Jiv5kp}nuK51{9dZ#`$fdF$2-9-iaMSwe^OeabjoEu4lrkL$G&(PYE_xQ20fk7>M}mWkeZISefWP-)wVMEQ_kTAm zJv3O34@E=!=qI%BL)_DmwElTtQgs&Zh6)XhGRRKE3)(JIn<;)j$pZfE3#vpW`REE(HD8?wJ1nuKc%VWi|q*<(9L_)bB-7{lUja z3LClpcM$bI1v&pE?*gKuA6ga<_g^3ufN}n}-UHAJ#BzVLJP3s8-v(n^mLLeUc7rDX zD+?qWEoFm{-#v2#ID^ah@PUx?Av8JhUb7rEuVc-q>PtMofAysF`88+?S<_y^9* z<%4ipTdx8P1O#Mul6?v)K6u7Un;V&x4kyXp*rHNIIP@Yh0_7$5KvPS(5$1SA6| z14N#~TW1isoxcnj>63tscb!p_ukK_kj}pb?E`4pz5PA z(3@NuXR}1??7Sho z7cB+iU8w+~Vz+-A75{z$9=?}EY|==A(w?t;{a#NFP-kF!zdD!r1Ao?56WH$z5Hm3i zvY0icg_!=|u|U-y|6i~`+p#NIlH~Uv%t+y>MX@q0tzEq^uR8AeyxSOX@djT;>Cz|k zpT0%~I+16_f;LqPo9y#0desWUeA2Wsn8N__bJ^(@DLM!Hmi#ApaFH6|7Nvq}@VGOY5|#pq^k!%NaIZrlu1rld50OENnyj3O z;7tI=c>K1a>SQ4Iv0VPk9$ytIX%2e;@nqP~FLS0_QjmSAYU_o~-5c@c`w0X2Hc*hY zU+aUXc3(~m>BAbuqhL?}!PRh>A6g-z#dG$$7OOSov_)0%RSzHZRQDWS44u*a4Im3k z=IH>-;E5lbEXO^In#eb7zqusv?1cmqEZEgr)%Vm5e=J` z$%4XxRs=+FdvH2l%JAS^P0AD|NH~-;8cTFTCJ{Z(Yv0@ErNI&P5rNlCv+LiwUIN2TIcBSnzF#Y=%1iWT0ud<%*j{VJE;;*PDK0B zssKS>UvDrK;bQIRO^Dn+jT}uBIO~W~P%4iUx~$)IU$GZPCh{)Hbl;67YJOHi+BAIu z9(im``;F{p6f@2;q+TTR=1nY6V&vqML`3MX3}7vjMI>sB)QX|d&~z^MQvxtfQFh3C zHG+qL<1>S+YsQ<_Is8|HnR4lG%FUa%=N(?Wa9x@jg(uwZ-=%ny;&5V_A=@2exdRf} z$@aUHM$+luX}{A*yM>8$WB;Z*6Yo;JB|^OeV~>CLkRof8L}#+Ybng7qttT!N^XHB+35LZ(@q_-w{*7VQ?u`k@9~>Ow9l!pI&QU%th<5NN0f~@ryOpKP-~- z87qRN!uc;*Dza-fwrV{8LOdlN{x5hc6vx}!yLEtq`kR)*Ra^LnSwVu3v=RJc6W7A7 z(s_=+YJc;;v~_L3hT{JaBGisS?|J0z0G;w@g#fT2PC!PAz&aB6FpZ2hczy5y{ih-aH>srM+kNn?S9t z&JA+?SIOoHNVMkW<`NSh>dx97ZO;Q}qla{_FHHgfJ+b~kzd2E6#+NQSkL~SV#qM-| zN(3YwKobV;E}^-2;-;g+*dXKq3wKK4&Vw3AQ;R| zNzqnSy}#z6n<4n<{QMk%8LBCtotwiSD((AQ7D_gCcIJSbqcwykB?Odyq>CpBf|s%J z@f6{R#`I?LC2If|;oiL~pajSndMc_+xdN@sXM6oc`Z9QAQu~{mxLl6xl#@T8n8)~d zc!DG>)|;`CDrN@ZYx=&4pMOV8xikjzQ=AURpBcvNYcoF|Xys`dsH<|y{B z-)3n9VuzzykgzRacfruHsXptqs7wF_vEDs4OQDu$(W>k~RifV=?+%{dd`nOWm0aCO zTy^!yI$PQ>NRu%MS?M`BCmI@FQM}a{Dl;R?$YEl9brSjI_HUsQYHTfi$l3WGSaO;z zfnh9Wq=bltHG)o&s!*~%R%VtI(w{D+P-V-&CL$tI9OP=Y!*Q<>q}MGM7c|)C z768(h-vUq_D@#i)ObQ8=LT>G3gp$0Xf~_pLBi_dXD2Uim43mnq@h8BeDZ!W#zw+1ubaW3vIu3+2+w^WK9n@iOjya3F%x4R2!e4vz~0s?7r1qwx6zjN;(eL=rvF=d$>CG_f8e-($44i;R4bFfTRSXQNM-t^-1nK=iLKJUQl_V zO>_x|VR@_T9zD<;T4v0NqN z{k=X{(S2QYXGe3@UZ_yU#l_K7AI2-84So1)zw|+a8LQi>Ujl&YzUqrVotWd->PJ8t zyE$VpU|%NfcQA&-eZvY&s21{!l;hax9Tlqu8EqZd21#NY4>PN&)qG2Je)I$H>muoI0-1p&J zhD8UW*2@0*AN+#k65>|~4aRjqZy+i#grJC7q`d)d`~Y!t#7xyb2V%tU^%$n#;Zmen zenh9g>pPH~AH0H3q2<-zxC)y+JE%ZN4js++zWX4=XKPc$!DH92@XX(AKe6F1LYi7XWeH~0&~<5+d}m|;C5dE&=i8{cb0E|+(cyM=ViN+A$A!` zcpep0Vl-*qJ(IRP`@RuQC&2XXo_L7DwZY6R9=E5)Ghx?7mnA3cT7z?FRGz+2DtrD# zn`Ajg-1qwcTwH)&rS<~=?gxzs48{)c7;P*z!vaV#*9LPSgauOh%2l~?1sbwNfKe+k zP>Sc|;KI6h-ZN%1+dm&%$Dp5aL+yH`HEDf7vhq3I=5{MF7gcC#wqoqJ0<88JaSn_f zgq#!U`4@j0$iGWXxAqP|=v8vg+~&K%#XlKP$@)|`%-+gw{ggW07)Un{-Clv%G^m9} zNhDj2&Uz-17^o*CNW{y^hZEotj16ajl~(QJc6@jG6ZdruKwg^vTWHbqIrYplcvf6^ zkAJrXp{~%#tCkxsUt9dtb_ixsOl3ERosvt5lfT_gGtY7V`CtW$BQe9HJ9^T=9(?UR z?SV}GW~^JCqvW<^=`RX;e=990XP6IXlHQiHvc8_k*CN5ry7xw7jx372g1{ocOk=}A zpk5uu=pTf6@AOMb3ZJT~%?QT95?0zUN>(3W;eZ}GoY4>$dtbdk%jb5#?1?#R|4&&) z+SkcR?K2M|+2CMP2n3RUJ0p$dW|gVC7X8X+3xMp(mAn%!-<+tLjH?D3M-rlF^K$#o zwg(hzOT6W6UU$wS=+ibrUJ-xzA6v zh3wSQxJPXN*PeVL;e zch`c@{|bxNsT*HQ99vhG0>sxfiF#BxQd_?rh`LcA3nP!w2H zAI`XfYE)OVcy@ZWBH0c6jOX)&Y>Y(oOE31tJ7K%)bK5~x<^(ah-}?LKt$8bzNo+Zu zL3%&#I`ZIIp1;^K_-=20JamL2v!@v-GM5`VK+^cB%{pClW#b>pi;?5K!0F6qWuMcd zS_IzG?3mL&nJFan^F2D%IVQCr#O|vu+){^`I=&*zi*aE6Z{_T7o$5wa8 zr!^zlc`l=rHwEyfnW0v8LLo>^PQ+yVD~*vwsceE=>yM2ZwcGo0#srx^7Gj^pQhHS- zdy*qv!A(%#DKc0gBe^~^lgTWWlRv*T{bgA&$aZ}{s&8_j!|wb@9EdngL?jDy)&t{( zBWn87_hvqPIZGBI+*+?NOr!Z%NrtV@(jLFhl`DbhXlX6`y(k#WL!2O3gFGNp_HeICwZS|>hK!OSywj2CrdJSMvyDchBh2w5 zzc(C__fy9GGw)wC5>ZW4|-&dy@Ejl@IM&@83dKmnV%>VdExyY5xTnGEk zUT}lnI!N>HM7hFCfnchy0pNS|eW)09J3xeeUS&J$V+&TeHqpCY3~kH7j7;l@XK(o@ zflAiax^!ct%74=PL0?ofb6F6z8^>kQ5csSFqbTI$ubYD%lSBOA(UgdvYY^ z-a3(>ewTrseyMGku;=OykWD%OmrMezzCz}T?!Q0>t8)0DoJCOZ&R^P$2sM>QJp~~R z>HXgoti!MWQn0GX2f}|q2e;P>hMcAbP3M(2cXr~`{Cv+d`3Z&6b^6oMlo$-FwL83$ z?e{;rO$Hn>tLHaK@@qE3PxJllLHlukgG>gfOl?PN5z|ud;i!fxF~E z8Lc*u5ve`5^U@+^k!Ce{G`q}V;M1s;xL;zX1ban??#povwM*b`n?l&M4^Yf#-`}E? zX(!;CZtd6C0xGQ1l7k(fO?orP&F+q<4&_CL7Rz;YEG}FsvQ2S?)Tr{09^e)st|sz18SQ%Emz%gs_}MW zF1`*uM7@3}u5|eJsb1gE)-0KFjiVBaPOba;5I9)_zMf{Jt5)YhcVhk0Xd*K9*AX0A zt3yL1eE9_hIUn!R7Y_{yAdc(+0FQ_OmX%2V*4Y6UjeMc3&0VCSOW>4<_77Oy%M49PKsYA8Zbkn>9oK2`Q-rKJWJl;40(U%aKyzSAB}XD z;pjI|la(&oscpV-ejdwB(*NuH3`*(D6tpK2jTItM$1W~G;Gl^^t8-l-XZv-4hST|x zjJEdT!Q{mUOOZ^sec0NlRZClC;903F`duun_KTxV&Sg__(9`(Esg|IOo{H4AHt*GW zUqZft?D6#MeIX#t`gMRn;Q=^yquH`*`7@jKQdf6g-bIl3&LRzQmWRhc?EHDj znhTEI2%~Czw*8gOO_}9>JK=O9LXIz%T5}$ZhOFYN6H&?Q=uqm%;n3s*aVQijk=!N@ zPOK17EVfur7K!4pH8-%ft^x`MkeN1!iB-*$`4U~UJ0rVZ>-%tOjtvgH0Ovs<4!qzr zzTey3Z8FF2lN9Mb2HV!~*9SG?5DdIBo$ho|uCt!;afk8pHOYxs*ovd$x#1{pM_7Rl zI64A=9Fi_A7Y8-%40>+e=^Pr32e-+|S(d92lK@xsa(4DoQ=0}AoNX=Tnf!2JM9=IU zTDz&7PSz@qcAR|uCSOpi)Np>$6pbtu&yJk@fTaOC7k^*?jwQH@IB5W!OrcZ}G%#Fd zhLa&dMNb$RW|JlqmJjBdIZZxAWTROBK)TohjdW13VtG*IBEp=N)4Q0(7OGrk`l7)r zNJk3@`*g4AXtcC|Gb;?EDq>?*kH{W?!%g@_k$}p<6bEO};lvlG5DT35^5a++9oEod znnLl;&@ETi2A*CRKI6k~xs9p=(UHr08(g_6H8glkzE{!E+Q9)Crrnk+0|lC`jH|d% z#9fo`qi4(A;v1C?#|qD!sN(8a`2H|-s^@$@-K8rt7{(b2KnBYup2(R@=Os9#;MWrn z5$0H1U1c|(GX8!72v7sO%rK7OjIlqOze*mTK&GV-GKI;tN)sirH(VEm0l`5gfV7fO zq+=SY2_!{+Y?W?TD&BK?ESDL2a(eVyTwJ8AqM|eUOoGvBp8;PCANj^S4+nR>3QiJ}nJe^U- z?RKV7F?0ZXX=2KAag%KSKE1@u*#0#7=A&ru4?5U5C3K_5l=U%=@>qEC5@+KNk4&0; zl_(^y21b94GXrpLSeE>IP*XoH3sz>8U9SLYcnyu)_hT^Vo>7}Gb=fp{?X9+IMKG?V zN&HX>YSbeS`$i3&aUB zy9*yD#K7$Jy5(1lr-}u9{p$Lw3txgPhMSr~@V+?Jm;QAeh{vodwkI@7wuaNB^PZ2< z`tmD5L1>hJpgI2;VJO*E=F(WOq)^s8;KG=O? z)jWo`cR=|%tfsH0B=cN3IvxLR64)G5~o=Sl6#!27}A PDw4n}k(b##s_*{?Hegm4 diff --git a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml deleted file mode 100644 index 4d46658a78e..00000000000 --- a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.plantuml +++ /dev/null @@ -1,11 +0,0 @@ -@startuml -participant Client -participant Server - -Client -> Server : Make Sync Resquest -activate Server -note left of Client : Wait for Response -Server --> Client : Return Response -deactivate Server - -@enduml diff --git a/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.png b/source/Tutorials/Intermediate/Async-Service/images/sync-client-diagram.png deleted file mode 100644 index 03bcba0fdf67cc562cc72d3e368c45437fa92ad5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 9524 zcmch7by!sG*Y3(uRuTBe;dWck&BDpq+uqX34Wwx4Xz60+X8C}@+?(N{o13%iEnZ${doxEjcL#eO z3nvGUfgXCm46V&wJ-5G~gTR0tuMDGDHH}sz(bKIn&L23>;3^#Pbk~U6p@u9)Gu{rb zADE{W)m5k+A2~8B?N_EB&8JT4i+<8MFS}v2(D{prfM}`<>Qh%Q5I)Y zUCmQ;9c*L2cW5*8^v05Le{g-Sd*3Qe^+)b|7B7Cu_G+T(JXAcZ;8+8aZwS!P0h4jw-(-x3))!zFrC{TyBuo{QmV!(kgYVZfFx}@1-FK#GHYWm$~a@ypaj> zQu{j5Dfa{?oHI>H>GSjWA56j2CMe%@-zaXz;Hh^y*XWDv-qDJQ+5vbB9f z6=A0=%b9Ietop#Y&$jRo?%>)OF!f-dkU1*~>VYVWqh7pw?ST5H~Co$cz>Nz7>Q(mlDK-GG*XMJ!}+u0C2o82!XVYg%XXn zq@bTXu`>y1*htVI=P_yAd`9mQeER(Pv6!p&!Xld)0;~i4M9{kURleiLU>?INR?fBQ zT>@eLc#vUh9J(W-X?J_OP`|=zZPWn+^1}Vm+uhG94Fj2VA^E_crk#&`qea$(Qf*J8 z5~m%r8!k_W!bo0suVMalGa70?R!Tx*P-1*hWs8|sPZ;g_S08**^*N~r0QKuP3uQ3~Y6$ z>C4Re^g{)>sY)UO#2KKesZ#Z$SB(ptz}7jCc91$0e2qklmUIN-^sUOlSAVf?OZ{?x zm=_M0g27Hy9xl7eUe(mZl<~}dS^vZg_gK~}KGz49AsYdXbzx(BUF#~HBEo+st!822 zc3D}4tgP(WQGmnB=aJ>**}1y-cqv*DM<#3N2}Ar6l@i20LLVmjD5q3APkA_>r7Qh; z7z^^gg8kPwS{N&fx+V@jXB$UGMn<0NV=<=$w8q=JyC0Lm=@BrJd?w7>*dqaF4n7g& zEnZIA+Ks`M)+Vvi5r}3E;IT&E#5p-Tcjc?qMT9#lrHPU(t&D^2NCaGdw(K3XdO-6u zdi{H9_a+BV@<3_&X_M4czifpQ<**IIfI;24T%Xfx3>!>U(ilOH2Z%bya`Ti&pnhH~HXfsQ&uD;7zt`7Y`jzPzh7|CW{MPd9#W3R z$H&L8C1j1~!D;O5bTVhO``oQOu&>Z`D98@nP9*V4ETvnRo z&tCsVfal9ExQDQN?>zUMjBIjyd%GQHPMTAbO2&q$EDkybkB0JzyT9{V8t7|#)_-nZ z@?dH<|W05Z&RG=9Tvg*QoS*rvtO-QMJmsPVHg#?neClQoRjY8ksW@(m+ zLNq7GLYJ@o4=Wl1@w2A!x!V?wH+5H#1UWr=6jM(R%?iPzpp(jAyJFoKLdMC zPsc0R+SZ#|9oVXDzkKjNYfQMMcH@q=w!q_aD7JPW8RzKcw`z@ZVkJnW)#L~FF1n2& ztG-af3ah9QqZ}?e39nL9neg+oO1U=D*ZIn?pCg*f#+w3~D#M-qDl>HAL7i5kh5Da4 zT6aFV7@#0D)ZEi#vVyj1RFD=$5?Tw@{Fg3Dk7Gy1W=08*6Wu*Wwj)1Il>YQ~b{c z5#u$F=AZLhVBu2(?kXepUsd3kw>i~V6) zQ@4$Y_dsl#!*1~K40Lsg`kz*M!N^pQC{*{!-cp=YY47yovkkzYzP`SdZk5U7lRTHj zo;uGha@(=eYRAbBkLEvK9SKtL8rOSmO-Yg#8#jd4IZih=cy3L(E)9g8%}kx2`_*7$ zw;w=`(MlqEV!XVA-QB43hb+4MRt5$WpK=xHCA^w#XN-M(e9X)kUxZr2Oga{OQ#$Br z)bjH3TJuP7kHb;8n++ZtX*I8nWZ*9~h#2YpwgD_rOBbe8)6y-_;YJKTftv34 z{YbTLZEL$YKcA>_;FN#M0RCEH60ljjl#`pA8oKb~hp@wh5Cg+Yi_U00_i6y)rr9JH ze)Ok@w)LlrsI2lE%zumuITm{~2aP9&HhtPJG;4dBeN#wihgcE6H;WJ}5GO77t zNX>)I$#2J<0h>~0GtGg9RrbUPq@K~vse*!ndWLA6kpNJ}ZXl^*5?|b7LVv4v;=M1c zBOxJCimp%rOXS#oc_-7qex0o0uZESdjPq1aKLKFjKETNfD{r=dJr*~pspK5jxO?ym4MDM$M1)2)# zT15so5mze7Tr%X`_PFg!1V@{ba&DPou2_SuQLUoNZr(M-&BAp~(~UU7Rc5m_AAry+ zHmYM1J32Ztsj$NL0N=D5CB@WX5iFoHhS~e`K&q?$ z^uoV->=W|fRVEkG#vlud07plCu47UHdDOpF&oo~tW&ke@WVRJV`Xmy&j}3*hfXu=| zPWwfsui@f;@H-JGAS5JIl-=1Il%`fo$Fb+si|2I)T5$lBIdzLmRoY`JD)t64#m8BM zae$EQ!VJDH$e{%4`B@y9nVGNlvaVi6>Iu}b6RCiZ@Xh)8ARHl%n(*cR-d>B$vf-yr z$LbT6Hi91Odb#Xwb?$4d$>^yDUqwa5iu}hHr~I%|TjxY(CZ>;3)Vk44`kHB@Y+w}H zBG=6kp@hD^qcD@{IrY}K;THUoRV|I-8UoI+FEcejKtTMAx9MC!zyXhU5WhtMp!}zXW<83@yus}8Q);%sTn|cN^FC``A z^=s?<_cIuPEOHd;S4Sd|U*6plcU#^zQRJ5Uz5Zkr>p5i}C~{Y+(8`PqnjQW?DA(l4 z$%!5rOTe2TYDQe8s*WT-BA43Q+TCedF8NIkDH|;M0w@+lR9u|e5Vjz04&zIE zY}am0T%}^pMMJ~DZBXmNl0bMCj6i$MtxvqSYes`*bIh{3SY{r@rKX12<53Q^1Yzen zcz{r#o%WVSpRQO&JwzVeuwo3|8x9GoA9nn zc=27a{WXOo(je-+x)n>maISL`Xn}%_nh9MV7XbVNrp2(^Ror`w#?fybl+29%hhGa z$yM+>;=o+Q7U(Cjc^SNw?^&`YUa+Yo2dbZtT$ zEthe3Mh9@dAzbhILeDqSZ`k?yvu-bTAT*LvFf_?^&qFTVW5bxS^77R1a+Wz=uwoP? z5LbUL>HArSR_sHFWT+(Ma)$U=G+xoUUN(`*;t8t@mUaFDOz?!1Pq5&>c+VHS*>~)z zRkJsY5~*J8)UbCLc>}hS{eHMIoRm~{D7B}WyS;t2vu782K*K+{Dkm2tZ6f6Q`Bk+u zZ(1zg%hwCU7M%(flTWh`Do%z2L@PgacH*h{Xlf3BjPh5{`2O)jHrA1kw|AutN$|eB zK&T$1^pe@IWfX1nV`0;FVuY|RGMe_=9Q(H_-rFp0xC0iI>Y2B&u%&y28N8s0IFECz z4_1rAP+NHOuJu&H>trJ{2_HV_oViU2<+UV95L4$PyIIvwt%2T9Sw$t}gb6l;f6lN} z{jP-xc3tumU!DTju$p^ih!KieKW>dDpt*hIlz47)ZS5&$2HEzZqJl@N=#H94H{xYw zVH5~{Jll4qWov-Iz(}t@nz|}KC1y6h-CQA$(eiYLxc#=dGdwenIio37%&gUU-9!^9 zx#=+7c#z0`^``-I&|2A(3%gE%k-oF_wm=Nu5%oWwuH0j4x&CKNf#JrIwyS=jsY%yH#$2fJe0$BUkXJ|CI zgyKOBt-q=bS3FvK_)+u7+uTwSD>gm7lQK@aTa``DMCg0Oydo-3&AQwd;X}nny&Wp> z#UMcv#7y6~oBXGch=7Id()EnY*1Qn7rtK{WfKjRUwAN@3GqM<_E>`o^nZ)Cb%MK7; z?cgwKJ$wJ~lb?*T{o4*>K>v~QN_~-Ng8=)4{7QX24sfnwlUB9kM$>s7SzUWi3`j1@ znTX-iod}HPF1`<8V!D)a{7#gYwT206p3!U8QUHrP+uv$!ohXw^Rzbd9=~P-KWg=Px z@+&NS_3_b?^gdqOCdx1*jySf~yH0;;>nLDjef?Ts8*_bwq+Vk2bnM)!K~zU=h%pRq z>fy|yp(mmei9nY8h6fcEPzzeb_x#vQR;|Q1Gx)jn;efbY94iz{*yeLPpj17qg)+b) z5GspjeFLN{tV*DDw?l#jS`BF3@Zt&&H{2P5Hd_j_s7ssbQ^LH4YQC#UKvix-_STWHC0219_pb?Y@ zH_bL9iOw5*XBlM?O1_iD_)a7g0{8Nm7`#?YPQDQ`h-0MFHg__0K?9W#|CsW8(YPC% zLUl7Ngf$MNjO+Fr?Y#QnFEQrXsDwrS2>>O?D`DG_HJg=!#RCuXe|81HWbe>UvrSD(sDeme#rTo5G+Z9Mx2x(NXF^3U&-SWHI?MFq};<3awvgY6X@DN6pI z;AkO-3jC9@zfu2x^yVKRM8c6o9^gMH%79ac{y#PV(fI#y;mla#mSW470^LDAe&56O zBE#y-%d@S|bOHc}cRSiNve_VcNz=H3@%Q=15;Y(n+*UpV>>-X>k$_6*4bZcinVB_R zo)%ON=LQD{a{=Vv;0$`>nbYZCKSYHWlhOPZA4^?~jb9`r3~x@>g^d17&0EU@0N$F+ zZD_796>xd}-tMcW>&foo+0ho>g%Lzg;=B1> zZ1fq%v`DVl(RHAkw6U=PT2%k-nZTWFYJfODqweVFn0xW^)vJZEGKVEa!`%&ho?CdAVQS+={HcQHX zyB)wIOl)k=&F|w6T`Yixb(>Q1rwWsph`8pmJj6&(Pw$3 znwq9U+>?QUfm;nnbZe2;GVl1xv*thy1x^-Z{lc6JK$#08rIy))EACEA(b()OqE1%eA1xdQR2TgdfNyHZLLy^Mtrk9X-e6}(sjDjt#Q4z-lEK}F0BImGk(6}c zg=B;bk8yq1s;i63m}TnYaBSY;1ed>!HV4xjA4Zppzn|ZBcrFdFab#o%znG`^RAr@* z{R^$=(9r7uuPBY$nymA5bF2JBdL1C6zOryrzY&q#C%!mc_4N{?W`KM*FfafJR~@c# z?@Dh>mYM|>6ma7Ceh=w0Ki;0bF*9{}arP`Egfi(uNW4a?g=DnI?;jqJ-#3qx|Iw4g zS#rOYsW>s1a>~Zj)3Zv+_=6iv%(Xx5X1a)zF~FT?W=szSuhWqd5uuG9JtLrv%$F+% z=%AOk_w1L*hzMU7IKyH8n;AO40zexC1jL{xPc-#PO#?see+R0?>FFr|9Z<3JxsHes z{)&nUKo2^pTnQk?7eg91pQaxSug@r8YS2k#OZ?;6)4g1V!)m=X2nI%Pnd0pkMmej_ z6=lw8@?V&xqsY5y=bY_dD6Ov?&r>2*T@ z#03JWnDi*rD0g>GTG=qjml(AWM^lmlz!Yg z+vdH?J1phU5&quyXp`iZE}weq=Hd5R!`-m5Ukd(?_G_3WInVuNg}qEaii*f5xGTcV7VC{+xe${QBtsW`@8E#>D*Ec12a^Vy%QQQ}j_&D=T2JC+TFm-s<-l({y8^2*`4|XN@85L0=f~mcMYmE8YGu zs|C}vnVmJlBBWz1q4+t65{1ufO+%TC^^TeAB%EjV4>zW}>uj8U51&eRu`%D@J^f}@ z2337QBW^cpElVPxD(|kTiB}I0*A2_0tw!;aVT~pwrDFtQfj2vQ5Oy&?C-w0|ux^E7 zjM7-PT04wFTVwq_VYXzocYU#-gPUfu1phuKtM!=BZRf>uK`xRhr;OXu@S!N-< zD(>dh(%VaIh-J^is`@;fl$2KUYNL9E+W

fI^+XlQaEgF1daWk@RvE8e3Wzff*PN z#|K86In|8U))=Zg=O-#D+=l6KkFMV;ceQ4%E2ufP3c@l5cJr4 zXn#Nc9duIamp!&(n_VrEykWjE^tHZSWdY_B3buR0Jsj;g$S62^7RG(9l2)h~f9{v)@lkLMO0Aly-}x zi#sDgnBA}hU?5xA>H-6_`{KKA;R{o{VHTqm)>)gA%+BKR0f%Q0YiOQK`|qe`V4im_ zGSCQl=BchC{*cdsLbqswh;&5zGWTT-4dqFAOiY$DL9j2N|2~XufC5^)0Vy2rv;R

UPDq+rKvd=jnw8-=lA(W^89ko`Wwi`qMBgZHA-Y8;CyYOXfAveQ*2zY2GY?bqr?A|fK^B!-GX>nubn%}3Mp zKvMbxxfzGbe|^Q^fd)GMdpA&^O6n)kBeWzvjT@z<6oP^pn@1Zgfz~Jf!mYMNa$9D;So`zt7nLfP_N{b)` ziFuoWx9&uwXd_U$k YBGbC7D^hX_9A5&VZmY`|%bGs<{9