From 6f4fda94ec40ebdd21cf0617b0bc2a9651578a1c Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 21 Jun 2022 08:19:54 +0200 Subject: [PATCH 01/94] remove fri mock from sonar sources --- sonar-project.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sonar-project.properties b/sonar-project.properties index 7f36ad17..e3277fab 100644 --- a/sonar-project.properties +++ b/sonar-project.properties @@ -9,7 +9,7 @@ sonar.modules=kuka_sunrise_control,kuka_sunrise_driver kuka_sunrise_control.sonar.projectName=kuka_sunrise_control kuka_sunrise_control.sonar.sources=./robot_control/src,./robot_control/include,./teleop_guided_robot/src,./teleop_guided_robot/include,./teleop_guided_robot/launch kuka_sunrise_driver.sonar.projectName=kuka_sunrise_driver -kuka_sunrise_driver.sonar.sources=./src,./include,./launch +kuka_sunrise_driver.sonar.sources=./src/kuka_sunrise,./include/kuka_sunrise,./launch # Encoding of the source code. Default is default system encoding sonar.sourceEncoding=UTF-8 From 33427d0de122119b860b8545cf60e28a3ad9d6d3 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 22 Jun 2022 11:00:14 +0200 Subject: [PATCH 02/94] add fri_client ros2 package --- fri_client/.gitignore | 2 + fri_client/CMakeLists.txt | 80 ++ fri_client/LICENSE | 21 + fri_client/README.md | 109 ++ fri_client/cmake/friConfig.cmake.in | 12 + .../include/fri/HWIFClientApplication.hpp | 32 + .../include/fri}/friClientApplication.h | 310 ++--- .../include/fri}/friClientIf.h | 404 +++--- .../include/fri}/friConnectionIf.h | 260 ++-- .../include/fri}/friException.h | 306 ++--- .../include/fri}/friLBRClient.h | 290 ++-- .../include/fri}/friLBRCommand.h | 325 +++-- .../include/fri}/friLBRState.h | 556 ++++---- .../include/fri}/friTransformationClient.h | 534 ++++---- .../include/fri}/friUdpConnection.h | 326 ++--- fri_client/package.xml | 15 + fri_client/src/FRIMessages.pb.c | 151 +++ fri_client/src/FRIMessages.pb.h | 303 +++++ fri_client/src/HWIFClientApplication.cpp | 117 ++ fri_client/src/friClientApplication.cpp | 211 +++ fri_client/src/friClientData.h | 240 ++++ fri_client/src/friCommandMessageEncoder.cpp | 121 ++ fri_client/src/friCommandMessageEncoder.h | 118 ++ fri_client/src/friLBRClient.cpp | 120 ++ fri_client/src/friLBRCommand.cpp | 113 ++ fri_client/src/friLBRState.cpp | 234 ++++ .../src/friMonitoringMessageDecoder.cpp | 145 ++ fri_client/src/friMonitoringMessageDecoder.h | 133 ++ fri_client/src/friTransformationClient.cpp | 191 +++ fri_client/src/friUdpConnection.cpp | 243 ++++ fri_client/src/pb_frimessages_callbacks.c | 267 ++++ fri_client/src/pb_frimessages_callbacks.h | 121 ++ fri_client/third_party/nanopb/.gitignore | 2 + fri_client/third_party/nanopb/CHANGELOG.txt | 150 +++ fri_client/third_party/nanopb/CMakeLists.txt | 103 ++ fri_client/third_party/nanopb/LICENSE.txt | 20 + fri_client/third_party/nanopb/README.txt | 61 + .../nanopb/cmake/NanoPBConfig.cmake.in | 10 + .../third_party/nanopb/include/nanopb/pb.h | 519 +++++++ .../nanopb/include/nanopb/pb_decode.h | 149 ++ .../nanopb/include/nanopb/pb_encode.h | 154 +++ .../nanopb/include/nanopb/pb_syshdr.h | 127 ++ .../nanopb/include/nanopb/pb_syshdr_win.h | 119 ++ fri_client/third_party/nanopb/src/pb_decode.c | 1198 +++++++++++++++++ fri_client/third_party/nanopb/src/pb_encode.c | 671 +++++++++ kuka_sunrise_driver/CMakeLists.txt | 48 +- .../include/fri_client/CPPLINT.cfg | 17 - .../include/kuka_sunrise/robot_commander.hpp | 2 +- .../kuka_sunrise/robot_control_client.hpp | 2 +- .../kuka_sunrise/robot_control_node.hpp | 4 +- .../include/kuka_sunrise/robot_observer.hpp | 2 +- .../src/fri_client_mock/CPPLINT.cfg | 17 - .../friClientApplication_mock.cpp | 73 - .../src/fri_client_mock/friLBRClient_mock.cpp | 63 - .../fri_client_mock/friLBRCommand_mock.cpp | 57 - .../src/fri_client_mock/friLBRState_mock.cpp | 141 -- .../friTransformationClient_mock.cpp | 110 -- .../fri_client_mock/friUdpConnection_mock.cpp | 64 - 58 files changed, 8048 insertions(+), 2245 deletions(-) create mode 100644 fri_client/.gitignore create mode 100644 fri_client/CMakeLists.txt create mode 100644 fri_client/LICENSE create mode 100644 fri_client/README.md create mode 100644 fri_client/cmake/friConfig.cmake.in create mode 100644 fri_client/include/fri/HWIFClientApplication.hpp rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friClientApplication.h (88%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friClientIf.h (91%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friConnectionIf.h (88%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friException.h (93%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friLBRClient.h (92%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friLBRCommand.h (90%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friLBRState.h (95%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friTransformationClient.h (96%) mode change 100755 => 100644 rename {kuka_sunrise_driver/include/fri_client => fri_client/include/fri}/friUdpConnection.h (94%) mode change 100755 => 100644 create mode 100644 fri_client/package.xml create mode 100644 fri_client/src/FRIMessages.pb.c create mode 100644 fri_client/src/FRIMessages.pb.h create mode 100644 fri_client/src/HWIFClientApplication.cpp create mode 100644 fri_client/src/friClientApplication.cpp create mode 100644 fri_client/src/friClientData.h create mode 100644 fri_client/src/friCommandMessageEncoder.cpp create mode 100644 fri_client/src/friCommandMessageEncoder.h create mode 100644 fri_client/src/friLBRClient.cpp create mode 100644 fri_client/src/friLBRCommand.cpp create mode 100644 fri_client/src/friLBRState.cpp create mode 100644 fri_client/src/friMonitoringMessageDecoder.cpp create mode 100644 fri_client/src/friMonitoringMessageDecoder.h create mode 100644 fri_client/src/friTransformationClient.cpp create mode 100644 fri_client/src/friUdpConnection.cpp create mode 100644 fri_client/src/pb_frimessages_callbacks.c create mode 100644 fri_client/src/pb_frimessages_callbacks.h create mode 100644 fri_client/third_party/nanopb/.gitignore create mode 100644 fri_client/third_party/nanopb/CHANGELOG.txt create mode 100644 fri_client/third_party/nanopb/CMakeLists.txt create mode 100644 fri_client/third_party/nanopb/LICENSE.txt create mode 100644 fri_client/third_party/nanopb/README.txt create mode 100644 fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in create mode 100644 fri_client/third_party/nanopb/include/nanopb/pb.h create mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_decode.h create mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_encode.h create mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h create mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h create mode 100644 fri_client/third_party/nanopb/src/pb_decode.c create mode 100644 fri_client/third_party/nanopb/src/pb_encode.c delete mode 100644 kuka_sunrise_driver/include/fri_client/CPPLINT.cfg delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/CPPLINT.cfg delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/friClientApplication_mock.cpp delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/friLBRClient_mock.cpp delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/friLBRCommand_mock.cpp delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/friLBRState_mock.cpp delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/friTransformationClient_mock.cpp delete mode 100644 kuka_sunrise_driver/src/fri_client_mock/friUdpConnection_mock.cpp diff --git a/fri_client/.gitignore b/fri_client/.gitignore new file mode 100644 index 00000000..d9dbb88d --- /dev/null +++ b/fri_client/.gitignore @@ -0,0 +1,2 @@ +### build +build \ No newline at end of file diff --git a/fri_client/CMakeLists.txt b/fri_client/CMakeLists.txt new file mode 100644 index 00000000..48cc0829 --- /dev/null +++ b/fri_client/CMakeLists.txt @@ -0,0 +1,80 @@ +cmake_minimum_required(VERSION 3.5) +project(fri) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) + +### Append CMAKE_MODULE_PATH by custom find file +list(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_SOURCE_DIR}/cmake) + +### Third party dependency +add_subdirectory(third_party/nanopb) + + +include_directories(include src) + +### Add the Fast Robot Interface libray +add_library(fri_client SHARED + src/HWIFClientApplication.cpp + src/friClientApplication.cpp + src/friCommandMessageEncoder.cpp + src/friLBRClient.cpp + src/friLBRCommand.cpp + src/friLBRState.cpp + src/FRIMessages.pb.c + src/friMonitoringMessageDecoder.cpp + src/friTransformationClient.cpp + src/friUdpConnection.cpp + src/pb_frimessages_callbacks.c +) + +if(MSVC) + target_compile_options(fri_client + PRIVATE + -DPB_SYSTEM_HEADER= + -DPB_FIELD_16BIT + -DWIN32 + -DHAVE_STDINT_H + -DHAVE_STDBOOL_H + ) +else() + target_compile_options(fri_client + PRIVATE + -O2 + -Wall + -DHAVE_SOCKLEN_T + -DPB_SYSTEM_HEADER= + -DPB_FIELD_16BIT + -DHAVE_STDINT_H + -DHAVE_STDDEF_H + -DHAVE_STDBOOL_H + -DHAVE_STDLIB_H + -DHAVE_STRING_H + ) +endif() + +target_link_libraries(fri_client PRIVATE NanoPB::nanopb) + +ament_export_targets(fri_client HAS_LIBRARY_TARGET) + +install( + TARGETS fri_client + EXPORT fri_client + LIBRARY DESTINATION lib + INCLUDES DESTINATION include +) + +ament_package() diff --git a/fri_client/LICENSE b/fri_client/LICENSE new file mode 100644 index 00000000..e212c0b0 --- /dev/null +++ b/fri_client/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2021 Martin Huber + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/fri_client/README.md b/fri_client/README.md new file mode 100644 index 00000000..2b1edabe --- /dev/null +++ b/fri_client/README.md @@ -0,0 +1,109 @@ +# Fast Robot Interface +The Fast Robot Interface (FRI) library allows for hard real time communication to the KUKA LBR Med, see KUKA's [paper](http://www.best-of-robotics.org/pages/publications/KUKA_FRI_from_WS_Proceedings_ICRA2010.pdf). This folder contains the C++ client side library to setup the UDP connection to the LBR Med. However, hard real time is only supported if the FRI is compiled on a real time OS. +## Build and Installation +Other than what KUKA provides, our FRI comes with CMake support. This allows for cross-platform compatability, therefore, the [Cross Platform Build and Installation](#cross-platform-build-and-installation) instructions are the same for Linux and Windows. However, the prerequisites are differntly obtained. How to obtain the prerequisites is explained in [Linux Prerequisites](#linux-prerequisites) and [Windows Prerequisites](#windows-prerequisites), respectively. +### Linux Prerequisites +Skip any of these if already satisfied. +* Install Git. In a terminal, run `sudo apt install git` +* Install CMake. In a terminal, run `sudo apt install cmake` +### Windows Prerequisites +Skip any of these if already satisfied. + * Install the new Windows Terminal. Search for `Microsoft Store` in Start and open it. Therein, search for `Windows Terminal`, and install it + * Install Chocolatey by following the [instructions](https://chocolatey.org/install) + * Install Git. In an administrative Windows Terminal, run `choco install git`. + * Install CMake. In an administrative Windows Terminal, run `choco install cmake`. Add CMake to your Path. Therefore, search for `Edit the system environment variables` in Start, and open it. Open `Environment Variables...`, and double click on `Path` under System variables. Click on `New`, and add `C:\Program Files\CMake\bin` (usually CMake is installed there, might differ) +### Cross Platform Build and Installation +Clone this repository +```shell +git clone https://github.com/KCL-BMEIS/FastRobotInterface.git +``` +Build and install the FRI library +```shell +cd FastRobotInterface +mkdir build +cd build +cmake .. +cmake --build . --config Release --target install # builds and installs the FRI library in Release mode +``` +## Usage +The FRI comes with [example apps](#example-apps). These apps require some [prerequisites](#prerequisites) that are explained below. +### Prerequisites +Follow the [Build and Installation](#build-and-installation) instructions for your OS. Install [Sunrise Workbench](#sunrise-workbench) on your computer. This step requires Windows as OS. +#### Sunrise Workbench +Sunrise Workbench is KUKA's Java IDE that allows you to program the LBR Med. +* Download it from the [RViM shared folder](https://emckclac.sharepoint.com/:u:/s/MT-BMEIS-RVIM/ETBf6gp3Ko5EvtJVziR8MZ4BLdeX8ysF13jTVmVreq0iZA?e=XJyagD) +* Extract the .zip file and run the Sunrise Workbench Setup +* Follow the install instructions +### Example Apps +Exemplary applications for the C++ client side are located inside the [apps](https://github.com/KCL-BMEIS/FastRobotInterface/tree/master/apps) folder. Each of these apps has a Java equivalent for the server side. +#### Connect Laptop +* Connect your laptop, therefore, establish an Ethernet connection to connector X66 at the KUKA controller +* The KUKA controller's default IP is 172.31.1.147. Configure the same network on your laptop, therefore + * On Windows + * Search for `View network connections` in Start and open it + * Right click on the Ethernet connection and open `Properties` + * Double click Internet Protocol Version 4 (TCP/IPv4) and set the IP address to `172.31.1.148` and the Subnet mask to `255.255.0.0` + * On Ubuntu 16 (might differ for other Linux distributions) + * Search for `System Settings` and open it + * Go to Network -> Wired -> Options + * Go to the IPv4 Settings tab and set the IP address to `172.31.1.148` and the Netmask to `255.255.0.0` +#### Server Side - KUKA Controller +You will have to follow the instructions in [Connect Laptop](#connect-laptop). The FRI has to be installed on the controller. Therefore, the [Sunrise Workbench](#sunrise-workbench) IDE is used. +* Open the Sunrise Workbench +* Create a new project, therefore + * Click File -> New -> Sunrise project + * Leave the default IP (172.31.1.147) and click Next + * Give your project a name, e.g. FRI and click Next + * Select LBR Med 7 R800 and click Next + * Under Media Flange, select Medien-Flansch Inside elektrisch, and click Next + * Click Finish (might take some time). Select RoboticsAPI Application, and press Next + * Click Finish +* Setup the KUKA controller, therefore + * Double click the StationSetup.cat under FRI in the Package Explorer and add the LBR Med 7 R800 to the Topolgy (below left) + * Remove the LBR_Med_7_R800_2, which has no Media Flange, and which we are not using (below right) +
+

+
+
+ * In the Software tab, make sure that the checker boxes for the FRI extensions are selected (below left) + * In the Configurations tab, make sure that the IP is set to 172.31.1.147 (below right) + * Save the StationSetup.cat via `Ctrl + s` +
+

+
+
+ * In the Installation tab, click Install (below left) + * Synchronize your project with the KUKA controller (below right) +
+

+
+
+#### Client Side - Laptop +You will have to follow the instructions in [Connect Laptop](#connect-laptop), and make sure that the FRI was installed to the KUKA controller, according to [Server Side - KUKA Controller](#server-side---kuka-controller). The client side requires to build the [apps](https://github.com/KCL-BMEIS/FastRobotInterface/tree/master/apps), which requires that the FRI was installed according to [Build and Installation](#build-and-installation). Then, open a terminal and do +```shell +cd apps +mkdir build +cd build +cmake -DCMAKE_PREFIX_PATH='path/to/lib' .. # on Windows this should be 'C:\Program Files (x86)\FastRobotInterface' + # on Linux this should be '/usr/local' +cmake --build . --config Release # builds the apps in Release mode +``` +#### Run the Apps +To run one of the example [apps](https://github.com/KCL-BMEIS/FastRobotInterface/tree/master/apps), they have to be started on the smartHMI (KUKA's smartpad), as well as on the laptop. +* On the smartHMI + * Select an Application (left below), e.g. the LBRJointSineOverlay + * Press one of the enabling switches half way (grey buttons on the back of the smartHMI). The joint control A1-A7 will light up (center below) + * Press and hold the play button (below right), and the enabling switch +

+
+

+
+
+* On the laptop open a terminal, and run + +```shell +cd apps/build # on Linux +cd apps/build/Release # on Windows +./lbrjointsineoverlay +``` +The robot should now be controlled by your Laptop, well done 😄! For open questions please leave an [Issue](https://github.com/KCL-BMEIS/FastRobotInterface/issues). diff --git a/fri_client/cmake/friConfig.cmake.in b/fri_client/cmake/friConfig.cmake.in new file mode 100644 index 00000000..3e4266f4 --- /dev/null +++ b/fri_client/cmake/friConfig.cmake.in @@ -0,0 +1,12 @@ +get_filename_component(FRI_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) +include(CMakeFindDependencyMacro) + +list(APPEND CMAKE_MODULE_PATH ${FRI_CMAKE_DIR}) + +find_package(NanoPB 0.2.8 REQUIRED) + +if(NOT TARGET FRI::FRI) + include("${FRI_CMAKE_DIR}/FRITargets.cmake") +endif() + +set(FRI_LIBRARIES FRI::FRI) \ No newline at end of file diff --git a/fri_client/include/fri/HWIFClientApplication.hpp b/fri_client/include/fri/HWIFClientApplication.hpp new file mode 100644 index 00000000..8879dd2a --- /dev/null +++ b/fri_client/include/fri/HWIFClientApplication.hpp @@ -0,0 +1,32 @@ +#ifndef FRI__HWIFCLIENTAPPLICATION_HPP_ +#define FRI__HWIFCLIENTAPPLICATION_HPP_ + +#include + +#include +#include +#include +#include +#include + + +namespace KUKA { + namespace FRI { + + class HWIFClientApplication : public ClientApplication { + public: + HWIFClientApplication(IConnection& connection, IClient& client); + + bool client_app_read(); + void client_app_update(); + bool client_app_write(); + + private: + int size_; + }; + + } +} // namespace KUKA::FRI + +#endif // FRI__HWIFCLIENTAPPLICATION_HPP_ + diff --git a/kuka_sunrise_driver/include/fri_client/friClientApplication.h b/fri_client/include/fri/friClientApplication.h old mode 100755 new mode 100644 similarity index 88% rename from kuka_sunrise_driver/include/fri_client/friClientApplication.h rename to fri_client/include/fri/friClientApplication.h index 499719ca..538e79d4 --- a/kuka_sunrise_driver/include/fri_client/friClientApplication.h +++ b/fri_client/include/fri/friClientApplication.h @@ -1,155 +1,155 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ - -#ifndef _KUKA_FRI_CLIENT_APPLICATION_H -#define _KUKA_FRI_CLIENT_APPLICATION_H - -/** Kuka namespace */ -namespace KUKA -{ -/** Fast Robot Interface (FRI) namespace */ -namespace FRI -{ - - // forward declarations - class IClient; - class TransformationClient; - class IConnection; - struct ClientData; - - /** - * \brief FRI client application class. - * - * A client application takes an instance of the IConnection interface and - * an instance of an IClient interface to provide the functionality - * needed to set up an FRI client application. It can be used to easily - * integrate the FRI client code within other applications. - * The algorithmic functionality of an FRI client application is implemented - * using the IClient interface. - */ - class ClientApplication - { - - public: - - /** - * \brief Constructor without transformation client. - * - * This constructor takes an instance of the IConnection interface and - * an instance of the IClient interface as parameters. - * @param connection FRI connection class - * @param client FRI client class - */ - ClientApplication(IConnection& connection, IClient& client); - - /** - * \brief Constructor with transformation client. - * - * This constructor takes an instance of the IConnection interface and - * an instance of the IClient interface and an instance of a - * TransformationClient as parameters. - * @param connection FRI connection class - * @param client FRI client class - * @param trafoClient FRI transformation client class - */ - ClientApplication(IConnection& connection, IClient& client, TransformationClient& trafoClient); - - /** \brief Destructor. */ - ~ClientApplication(); - - /** - * \brief Connect the FRI client application with a KUKA Sunrise controller. - * - * @param port The port ID - * @param remoteHost The address of the remote host - * @return True if connection was established - */ - bool connect(int port, const char *remoteHost = nullptr); - - /** - * \brief Disconnect the FRI client application from a KUKA Sunrise controller. - */ - void disconnect(); - - /** - * \brief Run a single processing step. - * - * The processing step consists of receiving a new FRI monitoring message, - * calling the corresponding client callback and sending the resulting - * FRI command message back to the KUKA Sunrise controller. - * @return True if all of the substeps succeeded. - */ - bool step(); - - protected: - - IConnection& _connection; //!< connection interface - IClient* _robotClient; //!< robot client interface - TransformationClient* _trafoClient; //!< transformation client interface - ClientData* _data; //!< client data structure (for internal use) - - }; - -} -} - - -#endif // _KUKA_FRI_CLIENT_APPLICATION_H - +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software “KUKA Sunrise.Connectivity FRI Client SDK” is targeted to work in +conjunction with the “KUKA Sunrise.Connectivity FastRobotInterface” toolkit. +In the following, the term “software” refers to all material directly +belonging to the provided SDK “Software development kit”, particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ + +#ifndef _KUKA_FRI_CLIENT_APPLICATION_H +#define _KUKA_FRI_CLIENT_APPLICATION_H + +/** Kuka namespace */ +namespace KUKA +{ +/** Fast Robot Interface (FRI) namespace */ +namespace FRI +{ + + // forward declarations + class IClient; + class TransformationClient; + class IConnection; + struct ClientData; + + /** + * \brief FRI client application class. + * + * A client application takes an instance of the IConnection interface and + * an instance of an IClient interface to provide the functionality + * needed to set up an FRI client application. It can be used to easily + * integrate the FRI client code within other applications. + * The algorithmic functionality of an FRI client application is implemented + * using the IClient interface. + */ + class ClientApplication + { + + public: + + /** + * \brief Constructor without transformation client. + * + * This constructor takes an instance of the IConnection interface and + * an instance of the IClient interface as parameters. + * @param connection FRI connection class + * @param client FRI client class + */ + ClientApplication(IConnection& connection, IClient& client); + + /** + * \brief Constructor with transformation client. + * + * This constructor takes an instance of the IConnection interface and + * an instance of the IClient interface and an instance of a + * TransformationClient as parameters. + * @param connection FRI connection class + * @param client FRI client class + * @param trafoClient FRI transformation client class + */ + ClientApplication(IConnection& connection, IClient& client, TransformationClient& trafoClient); + + /** \brief Destructor. */ + ~ClientApplication(); + + /** + * \brief Connect the FRI client application with a KUKA Sunrise controller. + * + * @param port The port ID + * @param remoteHost The address of the remote host + * @return True if connection was established + */ + bool connect(int port, const char *remoteHost = NULL); + + /** + * \brief Disconnect the FRI client application from a KUKA Sunrise controller. + */ + void disconnect(); + + /** + * \brief Run a single processing step. + * + * The processing step consists of receiving a new FRI monitoring message, + * calling the corresponding client callback and sending the resulting + * FRI command message back to the KUKA Sunrise controller. + * @return True if all of the substeps succeeded. + */ + bool step(); + + protected: + + IConnection& _connection; //!< connection interface + IClient* _robotClient; //!< robot client interface + TransformationClient* _trafoClient; //!< transformation client interface + ClientData* _data; //!< client data structure (for internal use) + + }; + +} +} + + +#endif // _KUKA_FRI_CLIENT_APPLICATION_H + diff --git a/kuka_sunrise_driver/include/fri_client/friClientIf.h b/fri_client/include/fri/friClientIf.h old mode 100755 new mode 100644 similarity index 91% rename from kuka_sunrise_driver/include/fri_client/friClientIf.h rename to fri_client/include/fri/friClientIf.h index 56710659..8830d010 --- a/kuka_sunrise_driver/include/fri_client/friClientIf.h +++ b/fri_client/include/fri/friClientIf.h @@ -1,202 +1,202 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_CLIENT_H -#define _KUKA_FRI_CLIENT_H - - - -/** Kuka namespace */ -namespace KUKA -{ -/** Fast Robot Interface (FRI) namespace */ -namespace FRI -{ - - // forward declarations - struct ClientData; - - - /** \brief Enumeration of the FRI session state. */ - enum ESessionState - { - IDLE = 0, //!< no session available - MONITORING_WAIT = 1, //!< monitoring mode with insufficient connection quality - MONITORING_READY = 2, //!< monitoring mode with connection quality sufficient for command mode - COMMANDING_WAIT = 3, //!< command mode about to start (overlay motion queued) - COMMANDING_ACTIVE = 4 //!< command mode active - }; - - /** \brief Enumeration of the FRI connection quality. */ - enum EConnectionQuality - { - POOR = 0, //!< poor connection quality - FAIR = 1, //!< connection quality insufficient for command mode - GOOD = 2, //!< connection quality sufficient for command mode - EXCELLENT = 3 //!< excellent connection quality - }; - - /** \brief Enumeration of the controller's safety state. */ - enum ESafetyState - { - NORMAL_OPERATION = 0, //!< No safety stop request present. - SAFETY_STOP_LEVEL_0 = 1,//!< Safety stop request STOP0 or STOP1 present. - SAFETY_STOP_LEVEL_1 = 2,//!< Safety stop request STOP1 (on-path) present. - SAFETY_STOP_LEVEL_2 = 3 //!< Safety stop request STOP2 present. - }; - - /** \brief Enumeration of the controller's current mode of operation. */ - enum EOperationMode - { - TEST_MODE_1 = 0, //!< test mode 1 with reduced speed (T1) - TEST_MODE_2 = 1, //!< test mode 2 (T2) - AUTOMATIC_MODE = 2 //!< automatic operation mode (AUT) - }; - - /** \brief Enumeration of a drive's state. */ - enum EDriveState - { - OFF = 0, //!< drive is not being used - TRANSITIONING = 1, //!< drive is in a transitioning state (before or after motion) - ACTIVE = 2 //!< drive is being actively commanded - }; - - /** \brief Enumeration of control mode. */ - enum EControlMode - { - POSITION_CONTROL_MODE = 0, //!< position control mode - CART_IMP_CONTROL_MODE = 1, //!< cartesian impedance control mode - JOINT_IMP_CONTROL_MODE = 2, //!< joint impedance control mode - NO_CONTROL = 3 //!< drives are not used - }; - - - /** \brief Enumeration of the client command mode. */ - enum EClientCommandMode - { - NO_COMMAND_MODE = 0, //!< no client command mode available - POSITION = 1, //!< commanding joint positions by the client - WRENCH = 2, //!< commanding wrenches and joint positions by the client - TORQUE = 3 //!< commanding joint torques and joint positions by the client - }; - - /** \brief Enumeration of the overlay type. */ - enum EOverlayType - { - NO_OVERLAY = 0, //!< no overlay type available - JOINT = 1, //!< joint overlay - CARTESIAN = 2 //!< cartesian overlay - }; - - - /** - * \brief FRI client interface. - * - * This is the callback interface that should be implemented by FRI clients. - * Callbacks are automatically called by the client application - * (ClientApplication) whenever new FRI messages arrive. - */ - class IClient - { - friend class ClientApplication; - - public: - - /** \brief Virtual destructor. */ - virtual ~IClient() {} - - /** - * \brief Callback that is called whenever the FRI session state changes. - * - * @param oldState previous FRI session state - * @param newState current FRI session state - */ - virtual void onStateChange(ESessionState oldState, ESessionState newState) = 0; - - /** - * \brief Callback for the FRI session states 'Monitoring Wait' and 'Monitoring Ready'. - */ - virtual void monitor() = 0; - - /** - * \brief Callback for the FRI session state 'Commanding Wait'. - */ - virtual void waitForCommand() = 0; - - /** - * \brief Callback for the FRI session state 'Commanding'. - */ - virtual void command() = 0; - - protected: - - /** - * \brief Method to create and initialize the client data structure (used internally). - * - * @return newly allocated client data structure - */ - virtual ClientData* createData() = 0; - - }; - -} -} - - -#endif // _KUKA_FRI_CLIENT_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software “KUKA Sunrise.Connectivity FRI Client SDK” is targeted to work in +conjunction with the “KUKA Sunrise.Connectivity FastRobotInterface” toolkit. +In the following, the term “software” refers to all material directly +belonging to the provided SDK “Software development kit”, particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_CLIENT_H +#define _KUKA_FRI_CLIENT_H + + + +/** Kuka namespace */ +namespace KUKA +{ +/** Fast Robot Interface (FRI) namespace */ +namespace FRI +{ + + // forward declarations + struct ClientData; + + + /** \brief Enumeration of the FRI session state. */ + enum ESessionState + { + IDLE = 0, //!< no session available + MONITORING_WAIT = 1, //!< monitoring mode with insufficient connection quality + MONITORING_READY = 2, //!< monitoring mode with connection quality sufficient for command mode + COMMANDING_WAIT = 3, //!< command mode about to start (overlay motion queued) + COMMANDING_ACTIVE = 4 //!< command mode active + }; + + /** \brief Enumeration of the FRI connection quality. */ + enum EConnectionQuality + { + POOR = 0, //!< poor connection quality + FAIR = 1, //!< connection quality insufficient for command mode + GOOD = 2, //!< connection quality sufficient for command mode + EXCELLENT = 3 //!< excellent connection quality + }; + + /** \brief Enumeration of the controller's safety state. */ + enum ESafetyState + { + NORMAL_OPERATION = 0, //!< No safety stop request present. + SAFETY_STOP_LEVEL_0 = 1,//!< Safety stop request STOP0 or STOP1 present. + SAFETY_STOP_LEVEL_1 = 2,//!< Safety stop request STOP1 (on-path) present. + SAFETY_STOP_LEVEL_2 = 3 //!< Safety stop request STOP2 present. + }; + + /** \brief Enumeration of the controller's current mode of operation. */ + enum EOperationMode + { + TEST_MODE_1 = 0, //!< test mode 1 with reduced speed (T1) + TEST_MODE_2 = 1, //!< test mode 2 (T2) + AUTOMATIC_MODE = 2 //!< automatic operation mode (AUT) + }; + + /** \brief Enumeration of a drive's state. */ + enum EDriveState + { + OFF = 0, //!< drive is not being used + TRANSITIONING = 1, //!< drive is in a transitioning state (before or after motion) + ACTIVE = 2 //!< drive is being actively commanded + }; + + /** \brief Enumeration of control mode. */ + enum EControlMode + { + POSITION_CONTROL_MODE = 0, //!< position control mode + CART_IMP_CONTROL_MODE = 1, //!< cartesian impedance control mode + JOINT_IMP_CONTROL_MODE = 2, //!< joint impedance control mode + NO_CONTROL = 3 //!< drives are not used + }; + + + /** \brief Enumeration of the client command mode. */ + enum EClientCommandMode + { + NO_COMMAND_MODE = 0, //!< no client command mode available + POSITION = 1, //!< commanding joint positions by the client + WRENCH = 2, //!< commanding wrenches and joint positions by the client + TORQUE = 3 //!< commanding joint torques and joint positions by the client + }; + + /** \brief Enumeration of the overlay type. */ + enum EOverlayType + { + NO_OVERLAY = 0, //!< no overlay type available + JOINT = 1, //!< joint overlay + CARTESIAN = 2 //!< cartesian overlay + }; + + + /** + * \brief FRI client interface. + * + * This is the callback interface that should be implemented by FRI clients. + * Callbacks are automatically called by the client application + * (ClientApplication) whenever new FRI messages arrive. + */ + class IClient + { + friend class ClientApplication; + + public: + + /** \brief Virtual destructor. */ + virtual ~IClient() {} + + /** + * \brief Callback that is called whenever the FRI session state changes. + * + * @param oldState previous FRI session state + * @param newState current FRI session state + */ + virtual void onStateChange(ESessionState oldState, ESessionState newState) = 0; + + /** + * \brief Callback for the FRI session states 'Monitoring Wait' and 'Monitoring Ready'. + */ + virtual void monitor() = 0; + + /** + * \brief Callback for the FRI session state 'Commanding Wait'. + */ + virtual void waitForCommand() = 0; + + /** + * \brief Callback for the FRI session state 'Commanding'. + */ + virtual void command() = 0; + + protected: + + /** + * \brief Method to create and initialize the client data structure (used internally). + * + * @return newly allocated client data structure + */ + virtual ClientData* createData() = 0; + + }; + +} +} + + +#endif // _KUKA_FRI_CLIENT_H diff --git a/kuka_sunrise_driver/include/fri_client/friConnectionIf.h b/fri_client/include/fri/friConnectionIf.h old mode 100755 new mode 100644 similarity index 88% rename from kuka_sunrise_driver/include/fri_client/friConnectionIf.h rename to fri_client/include/fri/friConnectionIf.h index 1d5332e2..2b4682fe --- a/kuka_sunrise_driver/include/fri_client/friConnectionIf.h +++ b/fri_client/include/fri/friConnectionIf.h @@ -1,130 +1,130 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_CONNECTION_H -#define _KUKA_FRI_CONNECTION_H - - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - /** - * \brief FRI connection interface. - * - * Connections to the KUKA Sunrise controller have to be implemented using - * this interface. - */ - class IConnection - { - - public: - - /** \brief Virtual destructor. */ - virtual ~IConnection() {} - - /** - * \brief Open a connection to the KUKA Sunrise controller. - * - * @param port The port ID - * @param remoteHost The address of the remote host - * @return True if connection was established - */ - virtual bool open(int port, const char *remoteHost) = 0; - - /** - * \brief Close a connection to the KUKA Sunrise controller. - */ - virtual void close() = 0; - - /** - * \brief Checks whether a connection to the KUKA Sunrise controller is established. - * - * @return True if connection is established - */ - virtual bool isOpen() const = 0; - - /** - * \brief Receive a new FRI monitoring message from the KUKA Sunrise controller. - * - * This method blocks until a new message arrives. - * @param buffer Pointer to the allocated buffer that will hold the FRI message - * @param maxSize Size in bytes of the allocated buffer - * @return Number of bytes received (0 when connection was terminated, negative in case of errors) - */ - virtual int receive(char *buffer, int maxSize) = 0; - - /** - * \brief Send a new FRI command message to the KUKA Sunrise controller. - * - * @param buffer Pointer to the buffer holding the FRI message - * @param size Size in bytes of the message to be send - * @return True if successful - */ - virtual bool send(const char* buffer, int size) = 0; - - }; - -} -} - - -#endif // _KUKA_FRI_CONNECTION_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software “KUKA Sunrise.Connectivity FRI Client SDK” is targeted to work in +conjunction with the “KUKA Sunrise.Connectivity FastRobotInterface” toolkit. +In the following, the term “software” refers to all material directly +belonging to the provided SDK “Software development kit”, particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_CONNECTION_H +#define _KUKA_FRI_CONNECTION_H + + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + /** + * \brief FRI connection interface. + * + * Connections to the KUKA Sunrise controller have to be implemented using + * this interface. + */ + class IConnection + { + + public: + + /** \brief Virtual destructor. */ + virtual ~IConnection() {} + + /** + * \brief Open a connection to the KUKA Sunrise controller. + * + * @param port The port ID + * @param remoteHost The address of the remote host + * @return True if connection was established + */ + virtual bool open(int port, const char *remoteHost) = 0; + + /** + * \brief Close a connection to the KUKA Sunrise controller. + */ + virtual void close() = 0; + + /** + * \brief Checks whether a connection to the KUKA Sunrise controller is established. + * + * @return True if connection is established + */ + virtual bool isOpen() const = 0; + + /** + * \brief Receive a new FRI monitoring message from the KUKA Sunrise controller. + * + * This method blocks until a new message arrives. + * @param buffer Pointer to the allocated buffer that will hold the FRI message + * @param maxSize Size in bytes of the allocated buffer + * @return Number of bytes received (0 when connection was terminated, negative in case of errors) + */ + virtual int receive(char *buffer, int maxSize) = 0; + + /** + * \brief Send a new FRI command message to the KUKA Sunrise controller. + * + * @param buffer Pointer to the buffer holding the FRI message + * @param size Size in bytes of the message to be send + * @return True if successful + */ + virtual bool send(const char* buffer, int size) = 0; + + }; + +} +} + + +#endif // _KUKA_FRI_CONNECTION_H diff --git a/kuka_sunrise_driver/include/fri_client/friException.h b/fri_client/include/fri/friException.h old mode 100755 new mode 100644 similarity index 93% rename from kuka_sunrise_driver/include/fri_client/friException.h rename to fri_client/include/fri/friException.h index 6d2c633b..03876b3b --- a/kuka_sunrise_driver/include/fri_client/friException.h +++ b/fri_client/include/fri/friException.h @@ -1,153 +1,153 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_EXCEPTION_H -#define _KUKA_FRI_EXCEPTION_H - -#include "stdio.h" - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - /** - * \brief Standard exception for the FRI Client - * - * \note For realtime considerations the internal message buffer is static. - * So don't use this exception in more than one thread per process. - */ - class FRIException - { - - public: - - /** - * \brief FRIException Constructor - * - * @param message Error message - */ - FRIException(const char* message) - { - strncpy(_buffer, message, sizeof(_buffer) - 1); - _buffer[sizeof(_buffer) - 1] = 0; // ensure string termination - printf("FRIException: "); - printf(_buffer); - printf("\n"); - } - - /** - * \brief FRIException Constructor - * - * @param message Error message which may contain one "%s" parameter - * @param param1 First format parameter for parameter message. - */ - FRIException(const char* message, const char* param1) - { -#ifdef _MSC_VER - _snprintf( // visual studio compilers (up to VS 2013) only know this method -#else - snprintf( -#endif - _buffer, sizeof(_buffer), message, param1); - printf("FRIException: "); - printf(_buffer); - printf("\n"); - } - - /** - * \brief FRIException Constructor - * - * @param message Error message which may contain two "%s" parameter - * @param param1 First format parameter for parameter message. - * @param param2 Second format parameter for parameter message. - */ - FRIException(const char* message, const char* param1, const char* param2) - { -#ifdef _MSC_VER - _snprintf( // visual studio compilers (up to VS 2013) only know this method -#else - snprintf( -#endif - _buffer, sizeof(_buffer), message, param1, param2); - printf("FRIException: "); - printf(_buffer); - printf("\n"); - } - - /** - * \brief Get error string. - * @return Error message stored in the exception. - */ - const char* getErrorMessage() const { return _buffer; } - - /** \brief Virtual destructor. */ - virtual ~FRIException() {} - - protected: - static char _buffer[1024]; - - }; - -} -} - - -#endif // _KUKA_FRI_EXCEPTION_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_EXCEPTION_H +#define _KUKA_FRI_EXCEPTION_H + +#include + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + /** + * \brief Standard exception for the FRI Client + * + * \note For realtime considerations the internal message buffer is static. + * So don't use this exception in more than one thread per process. + */ + class FRIException + { + + public: + + /** + * \brief FRIException Constructor + * + * @param message Error message + */ + FRIException(const char* message) + { + strncpy(_buffer, message, sizeof(_buffer) - 1); + _buffer[sizeof(_buffer) - 1] = 0; // ensure string termination + printf("FRIException: "); + printf(_buffer); + printf("\n"); + } + + /** + * \brief FRIException Constructor + * + * @param message Error message which may contain one "%s" parameter + * @param param1 First format parameter for parameter message. + */ + FRIException(const char* message, const char* param1) + { +#ifdef _MSC_VER + _snprintf( // visual studio compilers (up to VS 2013) only know this method +#else + snprintf( +#endif + _buffer, sizeof(_buffer), message, param1); + printf("FRIException: "); + printf(_buffer); + printf("\n"); + } + + /** + * \brief FRIException Constructor + * + * @param message Error message which may contain two "%s" parameter + * @param param1 First format parameter for parameter message. + * @param param2 Second format parameter for parameter message. + */ + FRIException(const char* message, const char* param1, const char* param2) + { +#ifdef _MSC_VER + _snprintf( // visual studio compilers (up to VS 2013) only know this method +#else + snprintf( +#endif + _buffer, sizeof(_buffer), message, param1, param2); + printf("FRIException: "); + printf(_buffer); + printf("\n"); + } + + /** + * \brief Get error string. + * @return Error message stored in the exception. + */ + const char* getErrorMessage() const { return _buffer; } + + /** \brief Virtual destructor. */ + virtual ~FRIException() {} + + protected: + static char _buffer[1024]; + + }; + +} +} + + +#endif // _KUKA_FRI_EXCEPTION_H diff --git a/kuka_sunrise_driver/include/fri_client/friLBRClient.h b/fri_client/include/fri/friLBRClient.h old mode 100755 new mode 100644 similarity index 92% rename from kuka_sunrise_driver/include/fri_client/friLBRClient.h rename to fri_client/include/fri/friLBRClient.h index 461efe1f..fc1b006e --- a/kuka_sunrise_driver/include/fri_client/friLBRClient.h +++ b/fri_client/include/fri/friLBRClient.h @@ -1,145 +1,145 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_LBR_CLIENT_H -#define _KUKA_FRI_LBR_CLIENT_H - -#include "friClientIf.h" -#include "friLBRState.h" -#include "friLBRCommand.h" - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - /** - * \brief Implementation of the IClient interface for the KUKA LBR (lightweight) robots. - * - * Provides access to the current LBR state and the possibility to send new - * commands to the LBR. - */ - class LBRClient : public IClient - { - - public: - - /** \brief Constructor. */ - LBRClient(); - - /** \brief Destructor. */ - ~LBRClient(); - - /** - * \brief Callback that is called whenever the FRI session state changes. - * - * @param oldState previous FRI session state - * @param newState current FRI session state - */ - virtual void onStateChange(ESessionState oldState, ESessionState newState); - - /** - * \brief Callback for the FRI session states 'Monitoring Wait' and 'Monitoring Ready'. - */ - virtual void monitor(); - - /** - * \brief Callback for the FRI session state 'Commanding Wait'. - */ - virtual void waitForCommand(); - - /** - * \brief Callback for the FRI session state 'Commanding'. - */ - virtual void command(); - - /** - * \brief Provide read access to the current robot state. - * - * @return Reference to the LBRState instance - */ - const LBRState& robotState() const { return _robotState; } - - /** - * \brief Provide write access to the robot commands. - * - * @return Reference to the LBRCommand instance - */ - LBRCommand& robotCommand() { return _robotCommand; } - - private: - - LBRState _robotState; //!< wrapper class for the FRI monitoring message - LBRCommand _robotCommand; //!< wrapper class for the FRI command message - - /** - * \brief Method to create and initialize the client data structure (used internally). - * - * @return newly allocated client data structure - */ - virtual ClientData* createData(); - - }; - -} -} - - -#endif // _KUKA_FRI_LBR_CLIENT_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_LBR_CLIENT_H +#define _KUKA_FRI_LBR_CLIENT_H + +#include +#include +#include + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + /** + * \brief Implementation of the IClient interface for the KUKA LBR (lightweight) robots. + * + * Provides access to the current LBR state and the possibility to send new + * commands to the LBR. + */ + class LBRClient : public IClient + { + + public: + + /** \brief Constructor. */ + LBRClient(); + + /** \brief Destructor. */ + ~LBRClient(); + + /** + * \brief Callback that is called whenever the FRI session state changes. + * + * @param oldState previous FRI session state + * @param newState current FRI session state + */ + virtual void onStateChange(ESessionState oldState, ESessionState newState); + + /** + * \brief Callback for the FRI session states 'Monitoring Wait' and 'Monitoring Ready'. + */ + virtual void monitor(); + + /** + * \brief Callback for the FRI session state 'Commanding Wait'. + */ + virtual void waitForCommand(); + + /** + * \brief Callback for the FRI session state 'Commanding'. + */ + virtual void command(); + + /** + * \brief Provide read access to the current robot state. + * + * @return Reference to the LBRState instance + */ + const LBRState& robotState() const { return _robotState; } + + /** + * \brief Provide write access to the robot commands. + * + * @return Reference to the LBRCommand instance + */ + LBRCommand& robotCommand() { return _robotCommand; } + + private: + + LBRState _robotState; //!< wrapper class for the FRI monitoring message + LBRCommand _robotCommand; //!< wrapper class for the FRI command message + + /** + * \brief Method to create and initialize the client data structure (used internally). + * + * @return newly allocated client data structure + */ + virtual ClientData* createData(); + + }; + +} +} + + +#endif // _KUKA_FRI_LBR_CLIENT_H diff --git a/kuka_sunrise_driver/include/fri_client/friLBRCommand.h b/fri_client/include/fri/friLBRCommand.h old mode 100755 new mode 100644 similarity index 90% rename from kuka_sunrise_driver/include/fri_client/friLBRCommand.h rename to fri_client/include/fri/friLBRCommand.h index 5ddbf8bc..752390b3 --- a/kuka_sunrise_driver/include/fri_client/friLBRCommand.h +++ b/fri_client/include/fri/friLBRCommand.h @@ -1,163 +1,162 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_LBR_COMMAND_H -#define _KUKA_FRI_LBR_COMMAND_H - - -// forward declarations -typedef struct _FRICommandMessage FRICommandMessage; -typedef struct _FRIMonitoringMessage FRIMonitoringMessage; - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - /** - * \brief Wrapper class for the FRI command message for a KUKA LBR (leightweight) robot. - */ - class LBRCommand - { - friend class LBRClient; - - public: - - /** - * \brief Set the joint positions for the current interpolation step. - * - * This method is only effective when the client is in a commanding state. - * @param values Array with the new joint positions (in rad) - */ - void setJointPosition(const double* values); - - /** - * \brief Set the applied wrench vector of the current interpolation step. - * - * The wrench vector consists of: - * [F_x, F_y, F_z, tau_A, tau_B, tau_C] - * - * F ... forces (in N) applied along the Cartesian axes of the - * currently used motion center. - * tau ... torques (in Nm) applied along the orientation angles - * (Euler angles A, B, C) of the currently used motion center. - * - * This method is only effective when the client is in a commanding state. - * The ControlMode of the robot has to be Cartesian impedance control mode. The - * Client Command Mode has to be wrench. - * - * @param wrench Applied Cartesian wrench vector. - */ - void setWrench(const double* wrench); - - /** - * \brief Set the applied joint torques for the current interpolation step. - * - * This method is only effective when the client is in a commanding state. - * The ControlMode of the robot has to be joint impedance control mode. The - * Client Command Mode has to be torque. - * - * @param torques Array with the applied torque values (in Nm) - */ - void setTorque(const double* torques); - - /** - * \brief Set boolean output value. - * - * @throw FRIException Throws a FRIException if more outputs are set than can be registered. - * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @param value Boolean value to set. - */ - void setBooleanIOValue(const char* name, const bool value); - - /** - * \brief Set digital output value. - * - * @throw FRIException Throws a FRIException if more outputs are set than can be registered. - * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @param value Digital value to set. - */ - void setDigitalIOValue(const char* name, const unsigned long long value); - - /** - * \brief Set analog output value. - * - * @throw FRIException Throws a FRIException if more outputs are set than can be registered. - * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @param value Analog value to set. - */ - void setAnalogIOValue(const char* name, const double value); - - protected: - - static const int LBRCOMMANDMESSAGEID = 0x34001; //!< type identifier for the FRI command message corresponding to a KUKA LBR robot - FRICommandMessage* _cmdMessage; //!< FRI command message (protobuf struct) - FRIMonitoringMessage* _monMessage; //!< FRI monitoring message (protobuf struct) - - }; - -} -} - - -#endif // _KUKA_FRI_LBR_COMMAND_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software “KUKA Sunrise.Connectivity FRI Client SDK” is targeted to work in +conjunction with the “KUKA Sunrise.Connectivity FastRobotInterface” toolkit. +In the following, the term “software” refers to all material directly +belonging to the provided SDK “Software development kit”, particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_LBR_COMMAND_H +#define _KUKA_FRI_LBR_COMMAND_H + + +// forward declarations +typedef struct _FRICommandMessage FRICommandMessage; + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + /** + * \brief Wrapper class for the FRI command message for a KUKA LBR (leightweight) robot. + */ + class LBRCommand + { + friend class LBRClient; + + public: + + /** + * \brief Set the joint positions for the current interpolation step. + * + * This method is only effective when the client is in a commanding state. + * @param values Array with the new joint positions (in rad) + */ + void setJointPosition(const double* values); + + /** + * \brief Set the applied wrench vector of the current interpolation step. + * + * The wrench vector consists of: + * [F_x, F_y, F_z, tau_A, tau_B, tau_C] + * + * F ... forces (in N) applied along the Cartesian axes of the + * currently used motion center. + * tau ... torques (in Nm) applied along the orientation angles + * (Euler angles A, B, C) of the currently used motion center. + * + * This method is only effective when the client is in a commanding state. + * The ControlMode of the robot has to be Cartesian impedance control mode. The + * Client Command Mode has to be wrench. + * + * @param wrench Applied Cartesian wrench vector. + */ + void setWrench(const double* wrench); + + /** + * \brief Set the applied joint torques for the current interpolation step. + * + * This method is only effective when the client is in a commanding state. + * The ControlMode of the robot has to be joint impedance control mode. The + * Client Command Mode has to be torque. + * + * @param torques Array with the applied torque values (in Nm) + */ + void setTorque(const double* torques); + + /** + * \brief Set boolean output value. + * + * @throw FRIException Throws a FRIException if more outputs are set than can be registered. + * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @param value Boolean value to set. + */ + void setBooleanIOValue(const char* name, const bool value); + + /** + * \brief Set digital output value. + * + * @throw FRIException Throws a FRIException if more outputs are set than can be registered. + * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @param value Digital value to set. + */ + void setDigitalIOValue(const char* name, const unsigned long long value); + + /** + * \brief Set analog output value. + * + * @throw FRIException Throws a FRIException if more outputs are set than can be registered. + * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @param value Analog value to set. + */ + void setAnalogIOValue(const char* name, const double value); + + protected: + + static const int LBRCOMMANDMESSAGEID = 0x34001; //!< type identifier for the FRI command message corresponding to a KUKA LBR robot + FRICommandMessage* _cmdMessage; //!< FRI command message (protobuf struct) + FRIMonitoringMessage* _monMessage; //!< FRI monitoring message (protobuf struct) + + }; + +} +} + + +#endif // _KUKA_FRI_LBR_COMMAND_H diff --git a/kuka_sunrise_driver/include/fri_client/friLBRState.h b/fri_client/include/fri/friLBRState.h old mode 100755 new mode 100644 similarity index 95% rename from kuka_sunrise_driver/include/fri_client/friLBRState.h rename to fri_client/include/fri/friLBRState.h index 97a2a03e..a70b3db2 --- a/kuka_sunrise_driver/include/fri_client/friLBRState.h +++ b/fri_client/include/fri/friLBRState.h @@ -1,278 +1,278 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_LBR_STATE_H -#define _KUKA_FRI_LBR_STATE_H - -#include "friClientIf.h" - -// forward declarations -typedef struct _FRIMonitoringMessage FRIMonitoringMessage; - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - /** - * \brief Wrapper class for the FRI monitoring message for a KUKA LBR (leightweight) robot. - */ - class LBRState - { - friend class LBRClient; - - public: - - enum - { - NUMBER_OF_JOINTS = 7 //!< number of axes of the KUKA LBR robot - }; - - LBRState(); - - /** - * \brief Get the sample time in seconds. - * - * This is the period in which the KUKA Sunrise controller is sending - * FRI packets. - * @return sample time in seconds - */ - double getSampleTime() const; // sec - - /** - * \brief Get the current FRI session state. - * - * @return current FRI session state - */ - ESessionState getSessionState() const; - - /** - * \brief Get the current FRI connection quality. - * - * @return current FRI connection quality - */ - EConnectionQuality getConnectionQuality() const; - - /** - * \brief Get the current safety state of the KUKA Sunrise controller. - * - * @return current safety state - */ - ESafetyState getSafetyState() const; - - /** - * \brief Get the current operation mode of the KUKA Sunrise controller. - * - * @return current operation mode - */ - EOperationMode getOperationMode() const; - - /** - * \brief Get the accumulated drive state over all drives of the KUKA LBR controller. - * - * If the drive states differ between drives, the following rule applies: - * 1) The drive state is OFF if all drives are OFF. - * 2) The drive state is ACTIVE if all drives are ACTIVE. - * 3) otherwise the drive state is TRANSITIONING. - * @return accumulated drive state - */ - EDriveState getDriveState() const; - - /** - * \brief Get the client command mode specified by the client. - * - * @return the client command mode specified by the client. - */ - EClientCommandMode getClientCommandMode() const; - - /** - * \brief Get the overlay type specified by the client. - * - * @return the overlay type specified by the client. - */ - EOverlayType getOverlayType() const; - - /** - * \brief Get the control mode of the KUKA LBR robot. - * - * @return current control mode of the KUKA LBR robot. - */ - EControlMode getControlMode() const; - - /** - * \brief Get the timestamp of the current robot state in Unix time. - * - * This method returns the seconds since 0:00, January 1st, 1970 (UTC). - * Use getTimestampNanoSec() to increase your timestamp resolution when - * seconds are insufficient. - * @return timestamp encoded as Unix time (seconds) - */ - unsigned int getTimestampSec() const; - - /** - * \brief Get the nanoseconds elapsed since the last second (in Unix time). - * - * This method complements getTimestampSec() to get a high resolution - * timestamp. - * @return timestamp encoded as Unix time (nanoseconds part) - */ - unsigned int getTimestampNanoSec() const; - - /** - * \brief Get the currently measured joint positions of the robot. - * - * @return array of the measured joint positions in radians - */ - const double* getMeasuredJointPosition() const; - - /** - * \brief Get the last commanded joint positions of the robot. - * - * @return array of the commanded joint positions in radians - */ - const double* getCommandedJointPosition() const; - - /** - * \brief Get the currently measured joint torques of the robot. - * - * @return array of the measured torques in Nm - */ - const double* getMeasuredTorque() const; - - /** - * \brief Get the last commanded joint torques of the robot. - * - * @return array of the commanded torques in Nm - */ - const double* getCommandedTorque() const; - - /** - * \brief Get the currently measured external joint torques of the robot. - * - * The external torques corresponds to the measured torques when removing - * the torques induced by the robot itself. - * @return array of the external torques in Nm - */ - const double* getExternalTorque() const; - - /** - * \brief Get the joint positions commanded by the interpolator. - * - * When commanding a motion overlay in your robot application, this method - * will give access to the joint positions currently commanded by the - * motion interpolator. - * @throw FRIException This method will throw an FRIException during monitoring mode. - * @return array of the ipo joint positions in radians - */ - const double* getIpoJointPosition() const; - - /** - * \brief Get an indicator for the current tracking performance of the commanded robot. - * - * The tracking performance is an indicator on how well the commanded robot - * is able to follow the commands of the FRI client. The best possible value - * 1.0 is reached when the robot executes the given commands instantaneously. - * The tracking performance drops towards 0 when latencies are induced, - * e.g. when the commanded velocity, acceleration or jerk exceeds the - * capabilities of the robot. - * The tracking performance will always be 0 when the session state does - * not equal COMMANDING_ACTIVE. - * @return current tracking performance - */ - double getTrackingPerformance() const; - - /** - * \brief Get boolean IO value. - * - * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @return Returns IO's boolean value. - */ - bool getBooleanIOValue(const char* name) const; - - /** - * \brief Get digital IO value. - * - * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @return Returns IO's digital value. - */ - unsigned long long getDigitalIOValue(const char* name) const; - - /** - * \brief Get analog IO value. - * - * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @return Returns IO's analog value. - */ - double getAnalogIOValue(const char* name) const; - - protected: - - static const int LBRMONITORMESSAGEID = 0x245142; //!< type identifier for the FRI monitoring message corresponding to a KUKA LBR robot - FRIMonitoringMessage* _message; //!< FRI monitoring message (protobuf struct) - }; - -} -} - - -#endif // _KUKA_FRI_LBR_STATE_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_LBR_STATE_H +#define _KUKA_FRI_LBR_STATE_H + +#include + +// forward declarations +typedef struct _FRIMonitoringMessage FRIMonitoringMessage; + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + /** + * \brief Wrapper class for the FRI monitoring message for a KUKA LBR (leightweight) robot. + */ + class LBRState + { + friend class LBRClient; + + public: + + enum + { + NUMBER_OF_JOINTS = 7 //!< number of axes of the KUKA LBR robot + }; + + LBRState(); + + /** + * \brief Get the sample time in seconds. + * + * This is the period in which the KUKA Sunrise controller is sending + * FRI packets. + * @return sample time in seconds + */ + double getSampleTime() const; // sec + + /** + * \brief Get the current FRI session state. + * + * @return current FRI session state + */ + ESessionState getSessionState() const; + + /** + * \brief Get the current FRI connection quality. + * + * @return current FRI connection quality + */ + EConnectionQuality getConnectionQuality() const; + + /** + * \brief Get the current safety state of the KUKA Sunrise controller. + * + * @return current safety state + */ + ESafetyState getSafetyState() const; + + /** + * \brief Get the current operation mode of the KUKA Sunrise controller. + * + * @return current operation mode + */ + EOperationMode getOperationMode() const; + + /** + * \brief Get the accumulated drive state over all drives of the KUKA LBR controller. + * + * If the drive states differ between drives, the following rule applies: + * 1) The drive state is OFF if all drives are OFF. + * 2) The drive state is ACTIVE if all drives are ACTIVE. + * 3) otherwise the drive state is TRANSITIONING. + * @return accumulated drive state + */ + EDriveState getDriveState() const; + + /** + * \brief Get the client command mode specified by the client. + * + * @return the client command mode specified by the client. + */ + EClientCommandMode getClientCommandMode() const; + + /** + * \brief Get the overlay type specified by the client. + * + * @return the overlay type specified by the client. + */ + EOverlayType getOverlayType() const; + + /** + * \brief Get the control mode of the KUKA LBR robot. + * + * @return current control mode of the KUKA LBR robot. + */ + EControlMode getControlMode() const; + + /** + * \brief Get the timestamp of the current robot state in Unix time. + * + * This method returns the seconds since 0:00, January 1st, 1970 (UTC). + * Use getTimestampNanoSec() to increase your timestamp resolution when + * seconds are insufficient. + * @return timestamp encoded as Unix time (seconds) + */ + unsigned int getTimestampSec() const; + + /** + * \brief Get the nanoseconds elapsed since the last second (in Unix time). + * + * This method complements getTimestampSec() to get a high resolution + * timestamp. + * @return timestamp encoded as Unix time (nanoseconds part) + */ + unsigned int getTimestampNanoSec() const; + + /** + * \brief Get the currently measured joint positions of the robot. + * + * @return array of the measured joint positions in radians + */ + const double* getMeasuredJointPosition() const; + + /** + * \brief Get the last commanded joint positions of the robot. + * + * @return array of the commanded joint positions in radians + */ + const double* getCommandedJointPosition() const; + + /** + * \brief Get the currently measured joint torques of the robot. + * + * @return array of the measured torques in Nm + */ + const double* getMeasuredTorque() const; + + /** + * \brief Get the last commanded joint torques of the robot. + * + * @return array of the commanded torques in Nm + */ + const double* getCommandedTorque() const; + + /** + * \brief Get the currently measured external joint torques of the robot. + * + * The external torques corresponds to the measured torques when removing + * the torques induced by the robot itself. + * @return array of the external torques in Nm + */ + const double* getExternalTorque() const; + + /** + * \brief Get the joint positions commanded by the interpolator. + * + * When commanding a motion overlay in your robot application, this method + * will give access to the joint positions currently commanded by the + * motion interpolator. + * @throw FRIException This method will throw an FRIException during monitoring mode. + * @return array of the ipo joint positions in radians + */ + const double* getIpoJointPosition() const; + + /** + * \brief Get an indicator for the current tracking performance of the commanded robot. + * + * The tracking performance is an indicator on how well the commanded robot + * is able to follow the commands of the FRI client. The best possible value + * 1.0 is reached when the robot executes the given commands instantaneously. + * The tracking performance drops towards 0 when latencies are induced, + * e.g. when the commanded velocity, acceleration or jerk exceeds the + * capabilities of the robot. + * The tracking performance will always be 0 when the session state does + * not equal COMMANDING_ACTIVE. + * @return current tracking performance + */ + double getTrackingPerformance() const; + + /** + * \brief Get boolean IO value. + * + * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @return Returns IO's boolean value. + */ + bool getBooleanIOValue(const char* name) const; + + /** + * \brief Get digital IO value. + * + * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @return Returns IO's digital value. + */ + unsigned long long getDigitalIOValue(const char* name) const; + + /** + * \brief Get analog IO value. + * + * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @return Returns IO's analog value. + */ + double getAnalogIOValue(const char* name) const; + + protected: + + static const int LBRMONITORMESSAGEID = 0x245142; //!< type identifier for the FRI monitoring message corresponding to a KUKA LBR robot + FRIMonitoringMessage* _message; //!< FRI monitoring message (protobuf struct) + }; + +} +} + + +#endif // _KUKA_FRI_LBR_STATE_H diff --git a/kuka_sunrise_driver/include/fri_client/friTransformationClient.h b/fri_client/include/fri/friTransformationClient.h old mode 100755 new mode 100644 similarity index 96% rename from kuka_sunrise_driver/include/fri_client/friTransformationClient.h rename to fri_client/include/fri/friTransformationClient.h index 53d6b26f..696d46b3 --- a/kuka_sunrise_driver/include/fri_client/friTransformationClient.h +++ b/fri_client/include/fri/friTransformationClient.h @@ -1,267 +1,267 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_TRANSFORMATION_CLIENT_H -#define _KUKA_FRI_TRANSFORMATION_CLIENT_H - -#include -#include "friClientIf.h" - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - // forward declaration - struct ClientData; - - /** - * \brief Abstract FRI transformation client. - * - * A transformation client enables the user to send transformation matrices cyclically to the - * KUKA Sunrise controller for manipulating the transformations of dynamic frames in the - * Sunrise scenegraph. - * Usually, these matrices will be provided by external sensors. - *
- * Custom transformation clients have to be derived from this class and need to - * implement the provide() callback. This callback is called once by the - * client application whenever a new FRI message arrives. - * - * This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions. - */ - class TransformationClient - { - - friend class ClientApplication; - - public: - - /** - *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * \brief Constructor. - **/ - TransformationClient(); - - /**
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * \brief Virtual destructor. - **/ - virtual ~TransformationClient(); - - /** - *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * \brief Callback which is called whenever a new FRI message arrives. - * - * In this callback all requested transformations have to be set. - * - * \see getRequestedTransformationIDs(), setTransformation() - */ - virtual void provide() = 0; - - /** - * \brief Get the sample time in seconds. - * - * This is the period in which the KUKA Sunrise controller is sending - * FRI packets. - * @return sample time in seconds - */ - double getSampleTime() const; // sec - - /** - * \brief Get the current FRI connection quality. - * - * @return current FRI connection quality - */ - EConnectionQuality getConnectionQuality() const; - - /** - *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * \brief Returns a vector of identifiers of all requested transformation matrices. - * - * The custom TransformationClient has to provide data for transformation matrices with these - * identifiers. - * - * @return reference to vector of IDs of requested transformations - */ - const std::vector& getRequestedTransformationIDs() const; - - /** - *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * - * \brief Get the timestamp of the current received FRI monitor message in Unix time. - * - * This method returns the seconds since 0:00, January 1st, 1970 (UTC). - * Use getTimestampNanoSec() to increase your timestamp resolution when - * seconds are insufficient. - * - * @return timestamp encoded as Unix time (seconds) - */ - const unsigned int getTimestampSec() const; - - /** - *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * \brief Get the nanoseconds elapsed since the last second (in Unix time). - * - * This method complements getTimestampSec() to get a high resolution - * timestamp. - * - * @return timestamp encoded as Unix time (nanoseconds part) - */ - const unsigned int getTimestampNanoSec() const; - - /** - *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
- * \brief Provides a requested transformation matrix. - * - * A transformation matrix has 3x4 elements. It consists of a rotational matrix (3x3 elements) - * and a translational vector (3x1 elements). The complete transformation matrix has the - * following structure:
- * [Transformation(3x4)] = [Rotation(3x3) | Translation(3x1) ] - *

- * All provided transformation matrices need a timestamp that corresponds to their - * time of acquisiton. This timestamp must be synchronized to the timestamp - * provided by the KUKA Sunrise controller (see getTimestampSec(), getTimestampNanoSec()). - *

- * If an update to the last transformation is not yet available when the provide() - * callback is executed, the last transformation (including its timestamp) should be - * repeated until a new transformation is available. - * - * @throw FRIException Throws a FRIException if the maximum number of transformations is exceeded. - * @param transformationID Identifier string of the transformation matrix - * @param transformationMatrix Provided transformation matrix - * @param timeSec Timestamp encoded as Unix time (seconds) - * @param timeNanoSec Timestamp encoded as Unix time (nanoseconds part) - */ - void setTransformation(const char* transformationID, const double transformationMatrix[3][4], - unsigned int timeSec, unsigned int timeNanoSec); - - /** - * \brief Set boolean output value. - * - * @throw FRIException Throws a FRIException if more outputs are set than can be registered. - * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @param value Boolean value to set. - */ - void setBooleanIOValue(const char* name, const bool value); - - /** - * \brief Set digital output value. - * - * @throw FRIException Throws a FRIException if more outputs are set than can be registered. - * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @param value Digital value to set. - */ - void setDigitalIOValue(const char* name, const unsigned long long value); - - /** - * \brief Set analog output value. - * - * @throw FRIException Throws a FRIException if more outputs are set than can be registered. - * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @param value Analog value to set. - */ - void setAnalogIOValue(const char* name, const double value); - - /** - * \brief Get boolean IO value. - * - * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @return Returns IO's boolean value. - */ - bool getBooleanIOValue(const char* name) const; - - /** - * \brief Get digital IO value. - * - * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @return Returns IO's digital value. - */ - unsigned long long getDigitalIOValue(const char* name) const; - - /** - * \brief Get analog IO value. - * - * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. - * @param name Full name of the IO (Syntax "IOGroupName.IOName"). - * @return Returns IO's analog value. - */ - double getAnalogIOValue(const char* name) const; - - private: - - ClientData* _data; //!< the client data structure - - /** - * \brief Method to link the client data structure (used internally). - * - * @param clientData the client data structure - */ - void linkData(ClientData* clientData); - - }; - -} -} - -#endif // _KUKA_FRI_TRANSFORMATION_CLIENT_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_TRANSFORMATION_CLIENT_H +#define _KUKA_FRI_TRANSFORMATION_CLIENT_H + +#include +#include + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + // forward declaration + struct ClientData; + + /** + * \brief Abstract FRI transformation client. + * + * A transformation client enables the user to send transformation matrices cyclically to the + * KUKA Sunrise controller for manipulating the transformations of dynamic frames in the + * Sunrise scenegraph. + * Usually, these matrices will be provided by external sensors. + *
+ * Custom transformation clients have to be derived from this class and need to + * implement the provide() callback. This callback is called once by the + * client application whenever a new FRI message arrives. + * + * This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions. + */ + class TransformationClient + { + + friend class ClientApplication; + + public: + + /** + *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * \brief Constructor. + **/ + TransformationClient(); + + /**
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * \brief Virtual destructor. + **/ + virtual ~TransformationClient(); + + /** + *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * \brief Callback which is called whenever a new FRI message arrives. + * + * In this callback all requested transformations have to be set. + * + * \see getRequestedTransformationIDs(), setTransformation() + */ + virtual void provide() = 0; + + /** + * \brief Get the sample time in seconds. + * + * This is the period in which the KUKA Sunrise controller is sending + * FRI packets. + * @return sample time in seconds + */ + double getSampleTime() const; // sec + + /** + * \brief Get the current FRI connection quality. + * + * @return current FRI connection quality + */ + EConnectionQuality getConnectionQuality() const; + + /** + *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * \brief Returns a vector of identifiers of all requested transformation matrices. + * + * The custom TransformationClient has to provide data for transformation matrices with these + * identifiers. + * + * @return reference to vector of IDs of requested transformations + */ + const std::vector& getRequestedTransformationIDs() const; + + /** + *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * + * \brief Get the timestamp of the current received FRI monitor message in Unix time. + * + * This method returns the seconds since 0:00, January 1st, 1970 (UTC). + * Use getTimestampNanoSec() to increase your timestamp resolution when + * seconds are insufficient. + * + * @return timestamp encoded as Unix time (seconds) + */ + const unsigned int getTimestampSec() const; + + /** + *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * \brief Get the nanoseconds elapsed since the last second (in Unix time). + * + * This method complements getTimestampSec() to get a high resolution + * timestamp. + * + * @return timestamp encoded as Unix time (nanoseconds part) + */ + const unsigned int getTimestampNanoSec() const; + + /** + *
This element is an undocumented internal feature. It is not intended to be used by applications as it might change or be removed in future versions.
+ * \brief Provides a requested transformation matrix. + * + * A transformation matrix has 3x4 elements. It consists of a rotational matrix (3x3 elements) + * and a translational vector (3x1 elements). The complete transformation matrix has the + * following structure:
+ * [Transformation(3x4)] = [Rotation(3x3) | Translation(3x1) ] + *

+ * All provided transformation matrices need a timestamp that corresponds to their + * time of acquisiton. This timestamp must be synchronized to the timestamp + * provided by the KUKA Sunrise controller (see getTimestampSec(), getTimestampNanoSec()). + *

+ * If an update to the last transformation is not yet available when the provide() + * callback is executed, the last transformation (including its timestamp) should be + * repeated until a new transformation is available. + * + * @throw FRIException Throws a FRIException if the maximum number of transformations is exceeded. + * @param transformationID Identifier string of the transformation matrix + * @param transformationMatrix Provided transformation matrix + * @param timeSec Timestamp encoded as Unix time (seconds) + * @param timeNanoSec Timestamp encoded as Unix time (nanoseconds part) + */ + void setTransformation(const char* transformationID, const double transformationMatrix[3][4], + unsigned int timeSec, unsigned int timeNanoSec); + + /** + * \brief Set boolean output value. + * + * @throw FRIException Throws a FRIException if more outputs are set than can be registered. + * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @param value Boolean value to set. + */ + void setBooleanIOValue(const char* name, const bool value); + + /** + * \brief Set digital output value. + * + * @throw FRIException Throws a FRIException if more outputs are set than can be registered. + * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @param value Digital value to set. + */ + void setDigitalIOValue(const char* name, const unsigned long long value); + + /** + * \brief Set analog output value. + * + * @throw FRIException Throws a FRIException if more outputs are set than can be registered. + * @throw FRIException May throw an FRIException if the IO is of wrong type, unknown or not an output. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @param value Analog value to set. + */ + void setAnalogIOValue(const char* name, const double value); + + /** + * \brief Get boolean IO value. + * + * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @return Returns IO's boolean value. + */ + bool getBooleanIOValue(const char* name) const; + + /** + * \brief Get digital IO value. + * + * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @return Returns IO's digital value. + */ + unsigned long long getDigitalIOValue(const char* name) const; + + /** + * \brief Get analog IO value. + * + * @throw FRIException May throw an FRIException if the IO is of wrong type or unknown. + * @param name Full name of the IO (Syntax "IOGroupName.IOName"). + * @return Returns IO's analog value. + */ + double getAnalogIOValue(const char* name) const; + + private: + + ClientData* _data; //!< the client data structure + + /** + * \brief Method to link the client data structure (used internally). + * + * @param clientData the client data structure + */ + void linkData(ClientData* clientData); + + }; + +} +} + +#endif // _KUKA_FRI_TRANSFORMATION_CLIENT_H diff --git a/kuka_sunrise_driver/include/fri_client/friUdpConnection.h b/fri_client/include/fri/friUdpConnection.h old mode 100755 new mode 100644 similarity index 94% rename from kuka_sunrise_driver/include/fri_client/friUdpConnection.h rename to fri_client/include/fri/friUdpConnection.h index 9766e7c5..b725b147 --- a/kuka_sunrise_driver/include/fri_client/friUdpConnection.h +++ b/fri_client/include/fri/friUdpConnection.h @@ -1,163 +1,163 @@ -/** - -The following license terms and conditions apply, unless a redistribution -agreement or other license is obtained by KUKA Deutschland GmbH, Augsburg, Germany. - -SCOPE - -The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in -conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. -In the following, the term "software" refers to all material directly -belonging to the provided SDK "Software development kit", particularly source -code, libraries, binaries, manuals and technical documentation. - -COPYRIGHT - -All Rights Reserved -Copyright (C) 2014-2018 -KUKA Deutschland GmbH -Augsburg, Germany - -LICENSE - -Redistribution and use of the software in source and binary forms, with or -without modification, are permitted provided that the following conditions are -met: -a) The software is used in conjunction with KUKA products only. -b) Redistributions of source code must retain the above copyright notice, this -list of conditions and the disclaimer. -c) Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the disclaimer in the documentation and/or other -materials provided with the distribution. Altered source code of the -redistribution must be made available upon request with the distribution. -d) Modification and contributions to the original software provided by KUKA -must be clearly marked and the authorship must be stated. -e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to -endorse or promote products derived from this software without specific prior -written permission. - -DISCLAIMER OF WARRANTY - -The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of -any kind, including without limitation the warranties of merchantability, -fitness for a particular purpose and non-infringement. -KUKA makes no warranty that the Software is free of defects or is suitable for -any particular purpose. In no event shall KUKA be responsible for loss or -damages arising from the installation or use of the Software, including but -not limited to any indirect, punitive, special, incidental or consequential -damages of any character including, without limitation, damages for loss of -goodwill, work stoppage, computer failure or malfunction, or any and all other -commercial damages or losses. -The entire risk to the quality and performance of the Software is not borne by -KUKA. Should the Software prove defective, KUKA is not liable for the entire -cost of any service and repair. - - - -\file -\version {1.16} -*/ -#ifndef _KUKA_FRI_UDP_CONNECTION_H -#define _KUKA_FRI_UDP_CONNECTION_H - -#include - -#ifdef _WIN32 - #include -#else - // if linux or a other unix system is used, select uses the following include - #ifdef __unix__ - #include - #endif - // for VxWorks - #ifdef VXWORKS - #include - #include - #endif - #include - #include -#endif - -#include "friConnectionIf.h" - -/** Kuka namespace */ -namespace KUKA -{ -namespace FRI -{ - - /** - * \brief This class implements the IConnection interface using UDP sockets. - */ - class UdpConnection : public IConnection - { - - public: - - /** - * \brief Constructor with an optional parameter for setting a receive timeout. - * - * @param receiveTimeout Timeout (in ms) for receiving a UDP message (0 = wait forever) - * */ - UdpConnection(unsigned int receiveTimeout = 0); - - /** \brief Destructor. */ - ~UdpConnection(); - - /** - * \brief Open a connection to the KUKA Sunrise controller. - * - * @param port The port ID for the connection - * @param controllerAddress The IPv4 address of the KUKA Sunrise controller. - * If NULL, the FRI Client accepts connections from any - * address. - * @return True if connection was established, false otherwise - */ - virtual bool open(int port, const char *controllerAddress = NULL); - - /** - * \brief Close a connection to the KUKA Sunrise controller. - */ - virtual void close(); - - /** - * \brief Checks whether a connection to the KUKA Sunrise controller is established. - * - * @return True if connection is established - */ - virtual bool isOpen() const; - - /** - * \brief Receive a new FRI monitoring message from the KUKA Sunrise controller. - * - * This method blocks until a new message arrives. - * @param buffer Pointer to the allocated buffer that will hold the FRI message - * @param maxSize Size in bytes of the allocated buffer - * @return Number of bytes received (0 when connection was terminated, - * negative in case of errors or receive timeout) - */ - virtual int receive(char *buffer, int maxSize); - - /** - * \brief Send a new FRI command message to the KUKA Sunrise controller. - * - * @param buffer Pointer to the buffer holding the FRI message - * @param size Size in bytes of the message to be send - * @return True if successful - */ - virtual bool send(const char* buffer, int size); - - private: - - int _udpSock; //!< UDP socket handle - struct sockaddr_in _controllerAddr; //!< the controller's socket address - unsigned int _receiveTimeout; - fd_set _filedescriptor; - - }; - -} -} - - -#endif // _KUKA_FRI_UDP_CONNECTION_H +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_UDP_CONNECTION_H +#define _KUKA_FRI_UDP_CONNECTION_H + +#include + +#ifdef _WIN32 + #include +#else + // if linux or a other unix system is used, select uses the following include + #ifdef __unix__ + #include + #endif + // for VxWorks + #ifdef VXWORKS + #include + #include + #endif + #include + #include +#endif + +#include + +/** Kuka namespace */ +namespace KUKA +{ +namespace FRI +{ + + /** + * \brief This class implements the IConnection interface using UDP sockets. + */ + class UdpConnection : public IConnection + { + + public: + + /** + * \brief Constructor with an optional parameter for setting a receive timeout. + * + * @param receiveTimeout Timeout (in ms) for receiving a UDP message (0 = wait forever) + * */ + UdpConnection(unsigned int receiveTimeout = 0); + + /** \brief Destructor. */ + ~UdpConnection(); + + /** + * \brief Open a connection to the KUKA Sunrise controller. + * + * @param port The port ID for the connection + * @param controllerAddress The IPv4 address of the KUKA Sunrise controller. + * If NULL, the FRI Client accepts connections from any + * address. + * @return True if connection was established, false otherwise + */ + virtual bool open(int port, const char *controllerAddress = NULL); + + /** + * \brief Close a connection to the KUKA Sunrise controller. + */ + virtual void close(); + + /** + * \brief Checks whether a connection to the KUKA Sunrise controller is established. + * + * @return True if connection is established + */ + virtual bool isOpen() const; + + /** + * \brief Receive a new FRI monitoring message from the KUKA Sunrise controller. + * + * This method blocks until a new message arrives. + * @param buffer Pointer to the allocated buffer that will hold the FRI message + * @param maxSize Size in bytes of the allocated buffer + * @return Number of bytes received (0 when connection was terminated, + * negative in case of errors or receive timeout) + */ + virtual int receive(char *buffer, int maxSize); + + /** + * \brief Send a new FRI command message to the KUKA Sunrise controller. + * + * @param buffer Pointer to the buffer holding the FRI message + * @param size Size in bytes of the message to be send + * @return True if successful + */ + virtual bool send(const char* buffer, int size); + + private: + + int _udpSock; //!< UDP socket handle + struct sockaddr_in _controllerAddr; //!< the controller's socket address + unsigned int _receiveTimeout; + fd_set _filedescriptor; + + }; + +} +} + + +#endif // _KUKA_FRI_UDP_CONNECTION_H diff --git a/fri_client/package.xml b/fri_client/package.xml new file mode 100644 index 00000000..4cf6d17d --- /dev/null +++ b/fri_client/package.xml @@ -0,0 +1,15 @@ + + + + fri + 0.0.0 + FRI client library + rosdeveloper + Apache 2.0 + + ament_cmake + + + ament_cmake + + diff --git a/fri_client/src/FRIMessages.pb.c b/fri_client/src/FRIMessages.pb.c new file mode 100644 index 00000000..6aa13458 --- /dev/null +++ b/fri_client/src/FRIMessages.pb.c @@ -0,0 +1,151 @@ +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.2.8 at Tue Feb 14 12:42:03 2017. */ + +#include + + + +const pb_field_t JointValues_fields[2] = { + PB_FIELD2( 1, DOUBLE , REPEATED, CALLBACK, FIRST, JointValues, value, value, 0), + PB_LAST_FIELD +}; + +const pb_field_t TimeStamp_fields[3] = { + PB_FIELD2( 1, UINT32 , REQUIRED, STATIC , FIRST, TimeStamp, sec, sec, 0), + PB_FIELD2( 2, UINT32 , REQUIRED, STATIC , OTHER, TimeStamp, nanosec, sec, 0), + PB_LAST_FIELD +}; + +const pb_field_t CartesianVector_fields[2] = { + PB_FIELD2( 1, DOUBLE , REPEATED, STATIC , FIRST, CartesianVector, element, element, 0), + PB_LAST_FIELD +}; + +const pb_field_t Checksum_fields[2] = { + PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, Checksum, crc32, crc32, 0), + PB_LAST_FIELD +}; + +const pb_field_t Transformation_fields[4] = { + PB_FIELD2( 1, STRING , REQUIRED, STATIC , FIRST, Transformation, name, name, 0), + PB_FIELD2( 2, DOUBLE , REPEATED, STATIC , OTHER, Transformation, matrix, name, 0), + PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, Transformation, timestamp, matrix, &TimeStamp_fields), + PB_LAST_FIELD +}; + +const pb_field_t FriIOValue_fields[6] = { + PB_FIELD2( 1, STRING , REQUIRED, STATIC , FIRST, FriIOValue, name, name, 0), + PB_FIELD2( 2, ENUM , REQUIRED, STATIC , OTHER, FriIOValue, type, name, 0), + PB_FIELD2( 3, ENUM , REQUIRED, STATIC , OTHER, FriIOValue, direction, type, 0), + PB_FIELD2( 4, UINT64 , OPTIONAL, STATIC , OTHER, FriIOValue, digitalValue, direction, 0), + PB_FIELD2( 5, DOUBLE , OPTIONAL, STATIC , OTHER, FriIOValue, analogValue, digitalValue, 0), + PB_LAST_FIELD +}; + +const pb_field_t MessageHeader_fields[4] = { + PB_FIELD2( 1, UINT32 , REQUIRED, STATIC , FIRST, MessageHeader, messageIdentifier, messageIdentifier, 0), + PB_FIELD2( 2, UINT32 , REQUIRED, STATIC , OTHER, MessageHeader, sequenceCounter, messageIdentifier, 0), + PB_FIELD2( 3, UINT32 , REQUIRED, STATIC , OTHER, MessageHeader, reflectedSequenceCounter, sequenceCounter, 0), + PB_LAST_FIELD +}; + +const pb_field_t ConnectionInfo_fields[5] = { + PB_FIELD2( 1, ENUM , REQUIRED, STATIC , FIRST, ConnectionInfo, sessionState, sessionState, 0), + PB_FIELD2( 2, ENUM , REQUIRED, STATIC , OTHER, ConnectionInfo, quality, sessionState, 0), + PB_FIELD2( 3, UINT32 , OPTIONAL, STATIC , OTHER, ConnectionInfo, sendPeriod, quality, 0), + PB_FIELD2( 4, UINT32 , OPTIONAL, STATIC , OTHER, ConnectionInfo, receiveMultiplier, sendPeriod, 0), + PB_LAST_FIELD +}; + +const pb_field_t RobotInfo_fields[6] = { + PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, RobotInfo, numberOfJoints, numberOfJoints, 0), + PB_FIELD2( 2, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, safetyState, numberOfJoints, 0), + PB_FIELD2( 5, ENUM , REPEATED, CALLBACK, OTHER, RobotInfo, driveState, safetyState, 0), + PB_FIELD2( 6, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, operationMode, driveState, 0), + PB_FIELD2( 7, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, controlMode, operationMode, 0), + PB_LAST_FIELD +}; + +const pb_field_t MessageMonitorData_fields[8] = { + PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageMonitorData, measuredJointPosition, measuredJointPosition, &JointValues_fields), + PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, measuredTorque, measuredJointPosition, &JointValues_fields), + PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, commandedJointPosition, measuredTorque, &JointValues_fields), + PB_FIELD2( 4, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, commandedTorque, commandedJointPosition, &JointValues_fields), + PB_FIELD2( 5, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, externalTorque, commandedTorque, &JointValues_fields), + PB_FIELD2( 8, MESSAGE , REPEATED, STATIC , OTHER, MessageMonitorData, readIORequest, externalTorque, &FriIOValue_fields), + PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, timestamp, readIORequest, &TimeStamp_fields), + PB_LAST_FIELD +}; + +const pb_field_t MessageIpoData_fields[5] = { + PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageIpoData, jointPosition, jointPosition, &JointValues_fields), + PB_FIELD2( 10, ENUM , OPTIONAL, STATIC , OTHER, MessageIpoData, clientCommandMode, jointPosition, 0), + PB_FIELD2( 11, ENUM , OPTIONAL, STATIC , OTHER, MessageIpoData, overlayType, clientCommandMode, 0), + PB_FIELD2( 12, DOUBLE , OPTIONAL, STATIC , OTHER, MessageIpoData, trackingPerformance, overlayType, 0), + PB_LAST_FIELD +}; + +const pb_field_t MessageCommandData_fields[6] = { + PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageCommandData, jointPosition, jointPosition, &JointValues_fields), + PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageCommandData, cartesianWrenchFeedForward, jointPosition, &CartesianVector_fields), + PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, MessageCommandData, jointTorque, cartesianWrenchFeedForward, &JointValues_fields), + PB_FIELD2( 4, MESSAGE , REPEATED, STATIC , OTHER, MessageCommandData, commandedTransformations, jointTorque, &Transformation_fields), + PB_FIELD2( 5, MESSAGE , REPEATED, STATIC , OTHER, MessageCommandData, writeIORequest, commandedTransformations, &FriIOValue_fields), + PB_LAST_FIELD +}; + +const pb_field_t MessageEndOf_fields[3] = { + PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, MessageEndOf, messageLength, messageLength, 0), + PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageEndOf, messageChecksum, messageLength, &Checksum_fields), + PB_LAST_FIELD +}; + +const pb_field_t FRIMonitoringMessage_fields[8] = { + PB_FIELD2( 1, MESSAGE , REQUIRED, STATIC , FIRST, FRIMonitoringMessage, header, header, &MessageHeader_fields), + PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, robotInfo, header, &RobotInfo_fields), + PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, monitorData, robotInfo, &MessageMonitorData_fields), + PB_FIELD2( 4, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, connectionInfo, monitorData, &ConnectionInfo_fields), + PB_FIELD2( 5, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, ipoData, connectionInfo, &MessageIpoData_fields), + PB_FIELD2( 6, MESSAGE , REPEATED, STATIC , OTHER, FRIMonitoringMessage, requestedTransformations, ipoData, &Transformation_fields), + PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, endOfMessageData, requestedTransformations, &MessageEndOf_fields), + PB_LAST_FIELD +}; + +const pb_field_t FRICommandMessage_fields[4] = { + PB_FIELD2( 1, MESSAGE , REQUIRED, STATIC , FIRST, FRICommandMessage, header, header, &MessageHeader_fields), + PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, FRICommandMessage, commandData, header, &MessageCommandData_fields), + PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, FRICommandMessage, endOfMessageData, commandData, &MessageEndOf_fields), + PB_LAST_FIELD +}; + + +/* Check that field information fits in pb_field_t */ +#if !defined(PB_FIELD_32BIT) +/* If you get an error here, it means that you need to define PB_FIELD_32BIT + * compile-time option. You can do that in pb.h or on compiler command line. + * + * The reason you need to do this is that some of your messages contain tag + * numbers or field sizes that are larger than what can fit in 8 or 16 bit + * field descriptors. + */ +STATIC_ASSERT((pb_membersize(Transformation, timestamp) < 65536 && pb_membersize(MessageMonitorData, measuredJointPosition) < 65536 && pb_membersize(MessageMonitorData, measuredTorque) < 65536 && pb_membersize(MessageMonitorData, commandedJointPosition) < 65536 && pb_membersize(MessageMonitorData, commandedTorque) < 65536 && pb_membersize(MessageMonitorData, externalTorque) < 65536 && pb_membersize(MessageMonitorData, readIORequest[0]) < 65536 && pb_membersize(MessageMonitorData, timestamp) < 65536 && pb_membersize(MessageIpoData, jointPosition) < 65536 && pb_membersize(MessageCommandData, jointPosition) < 65536 && pb_membersize(MessageCommandData, cartesianWrenchFeedForward) < 65536 && pb_membersize(MessageCommandData, jointTorque) < 65536 && pb_membersize(MessageCommandData, commandedTransformations[0]) < 65536 && pb_membersize(MessageCommandData, writeIORequest[0]) < 65536 && pb_membersize(MessageEndOf, messageChecksum) < 65536 && pb_membersize(FRIMonitoringMessage, header) < 65536 && pb_membersize(FRIMonitoringMessage, connectionInfo) < 65536 && pb_membersize(FRIMonitoringMessage, robotInfo) < 65536 && pb_membersize(FRIMonitoringMessage, monitorData) < 65536 && pb_membersize(FRIMonitoringMessage, ipoData) < 65536 && pb_membersize(FRIMonitoringMessage, requestedTransformations[0]) < 65536 && pb_membersize(FRIMonitoringMessage, endOfMessageData) < 65536 && pb_membersize(FRICommandMessage, header) < 65536 && pb_membersize(FRICommandMessage, commandData) < 65536 && pb_membersize(FRICommandMessage, endOfMessageData) < 65536), YOU_MUST_DEFINE_PB_FIELD_32BIT_FOR_MESSAGES_JointValues_TimeStamp_CartesianVector_Checksum_Transformation_FriIOValue_MessageHeader_ConnectionInfo_RobotInfo_MessageMonitorData_MessageIpoData_MessageCommandData_MessageEndOf_FRIMonitoringMessage_FRICommandMessage) +#endif + +#if !defined(PB_FIELD_16BIT) && !defined(PB_FIELD_32BIT) +/* If you get an error here, it means that you need to define PB_FIELD_16BIT + * compile-time option. You can do that in pb.h or on compiler command line. + * + * The reason you need to do this is that some of your messages contain tag + * numbers or field sizes that are larger than what can fit in the default + * 8 bit descriptors. + */ +STATIC_ASSERT((pb_membersize(Transformation, timestamp) < 256 && pb_membersize(MessageMonitorData, measuredJointPosition) < 256 && pb_membersize(MessageMonitorData, measuredTorque) < 256 && pb_membersize(MessageMonitorData, commandedJointPosition) < 256 && pb_membersize(MessageMonitorData, commandedTorque) < 256 && pb_membersize(MessageMonitorData, externalTorque) < 256 && pb_membersize(MessageMonitorData, readIORequest[0]) < 256 && pb_membersize(MessageMonitorData, timestamp) < 256 && pb_membersize(MessageIpoData, jointPosition) < 256 && pb_membersize(MessageCommandData, jointPosition) < 256 && pb_membersize(MessageCommandData, cartesianWrenchFeedForward) < 256 && pb_membersize(MessageCommandData, jointTorque) < 256 && pb_membersize(MessageCommandData, commandedTransformations[0]) < 256 && pb_membersize(MessageCommandData, writeIORequest[0]) < 256 && pb_membersize(MessageEndOf, messageChecksum) < 256 && pb_membersize(FRIMonitoringMessage, header) < 256 && pb_membersize(FRIMonitoringMessage, connectionInfo) < 256 && pb_membersize(FRIMonitoringMessage, robotInfo) < 256 && pb_membersize(FRIMonitoringMessage, monitorData) < 256 && pb_membersize(FRIMonitoringMessage, ipoData) < 256 && pb_membersize(FRIMonitoringMessage, requestedTransformations[0]) < 256 && pb_membersize(FRIMonitoringMessage, endOfMessageData) < 256 && pb_membersize(FRICommandMessage, header) < 256 && pb_membersize(FRICommandMessage, commandData) < 256 && pb_membersize(FRICommandMessage, endOfMessageData) < 256), YOU_MUST_DEFINE_PB_FIELD_16BIT_FOR_MESSAGES_JointValues_TimeStamp_CartesianVector_Checksum_Transformation_FriIOValue_MessageHeader_ConnectionInfo_RobotInfo_MessageMonitorData_MessageIpoData_MessageCommandData_MessageEndOf_FRIMonitoringMessage_FRICommandMessage) +#endif + + +/* On some platforms (such as AVR), double is really float. + * These are not directly supported by nanopb, but see example_avr_double. + * To get rid of this error, remove any double fields from your .proto. + */ +STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) + diff --git a/fri_client/src/FRIMessages.pb.h b/fri_client/src/FRIMessages.pb.h new file mode 100644 index 00000000..982abca1 --- /dev/null +++ b/fri_client/src/FRIMessages.pb.h @@ -0,0 +1,303 @@ +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.2.8 at Tue Feb 14 12:42:03 2017. */ + +#ifndef _PB_FRIMESSAGES_PB_H_ +#define _PB_FRIMESSAGES_PB_H_ +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* Enum definitions */ +typedef enum _FRISessionState { + FRISessionState_IDLE = 0, + FRISessionState_MONITORING_WAIT = 1, + FRISessionState_MONITORING_READY = 2, + FRISessionState_COMMANDING_WAIT = 3, + FRISessionState_COMMANDING_ACTIVE = 4 +} FRISessionState; + +typedef enum _FRIConnectionQuality { + FRIConnectionQuality_POOR = 0, + FRIConnectionQuality_FAIR = 1, + FRIConnectionQuality_GOOD = 2, + FRIConnectionQuality_EXCELLENT = 3 +} FRIConnectionQuality; + +typedef enum _SafetyState { + SafetyState_NORMAL_OPERATION = 0, + SafetyState_SAFETY_STOP_LEVEL_0 = 1, + SafetyState_SAFETY_STOP_LEVEL_1 = 2, + SafetyState_SAFETY_STOP_LEVEL_2 = 3 +} SafetyState; + +typedef enum _OperationMode { + OperationMode_TEST_MODE_1 = 0, + OperationMode_TEST_MODE_2 = 1, + OperationMode_AUTOMATIC_MODE = 2 +} OperationMode; + +typedef enum _DriveState { + DriveState_OFF = 0, + DriveState_TRANSITIONING = 1, + DriveState_ACTIVE = 2 +} DriveState; + +typedef enum _ControlMode { + ControlMode_POSITION_CONTROLMODE = 0, + ControlMode_CARTESIAN_IMPEDANCE_CONTROLMODE = 1, + ControlMode_JOINT_IMPEDANCE_CONTROLMODE = 2, + ControlMode_NO_CONTROLMODE = 3 +} ControlMode; + +typedef enum _ClientCommandMode { + ClientCommandMode_NO_COMMAND_MODE = 0, + ClientCommandMode_POSITION = 1, + ClientCommandMode_WRENCH = 2, + ClientCommandMode_TORQUE = 3 +} ClientCommandMode; + +typedef enum _OverlayType { + OverlayType_NO_OVERLAY = 0, + OverlayType_JOINT = 1, + OverlayType_CARTESIAN = 2 +} OverlayType; + +typedef enum _FriIOType { + FriIOType_BOOLEAN = 0, + FriIOType_DIGITAL = 1, + FriIOType_ANALOG = 2 +} FriIOType; + +typedef enum _FriIODirection { + FriIODirection_INPUT = 0, + FriIODirection_OUTPUT = 1 +} FriIODirection; + +/* Struct definitions */ +typedef struct _CartesianVector { + size_t element_count; + double element[6]; +} CartesianVector; + +typedef struct _Checksum { + bool has_crc32; + int32_t crc32; +} Checksum; + +typedef struct _ConnectionInfo { + FRISessionState sessionState; + FRIConnectionQuality quality; + bool has_sendPeriod; + uint32_t sendPeriod; + bool has_receiveMultiplier; + uint32_t receiveMultiplier; +} ConnectionInfo; + +typedef struct _FriIOValue { + char name[64]; + FriIOType type; + FriIODirection direction; + bool has_digitalValue; + uint64_t digitalValue; + bool has_analogValue; + double analogValue; +} FriIOValue; + +typedef struct _JointValues { + pb_callback_t value; +} JointValues; + +typedef struct _MessageHeader { + uint32_t messageIdentifier; + uint32_t sequenceCounter; + uint32_t reflectedSequenceCounter; +} MessageHeader; + +typedef struct _RobotInfo { + bool has_numberOfJoints; + int32_t numberOfJoints; + bool has_safetyState; + SafetyState safetyState; + pb_callback_t driveState; + bool has_operationMode; + OperationMode operationMode; + bool has_controlMode; + ControlMode controlMode; +} RobotInfo; + +typedef struct _TimeStamp { + uint32_t sec; + uint32_t nanosec; +} TimeStamp; + +typedef struct _MessageEndOf { + bool has_messageLength; + int32_t messageLength; + bool has_messageChecksum; + Checksum messageChecksum; +} MessageEndOf; + +typedef struct _MessageIpoData { + bool has_jointPosition; + JointValues jointPosition; + bool has_clientCommandMode; + ClientCommandMode clientCommandMode; + bool has_overlayType; + OverlayType overlayType; + bool has_trackingPerformance; + double trackingPerformance; +} MessageIpoData; + +typedef struct _MessageMonitorData { + bool has_measuredJointPosition; + JointValues measuredJointPosition; + bool has_measuredTorque; + JointValues measuredTorque; + bool has_commandedJointPosition; + JointValues commandedJointPosition; + bool has_commandedTorque; + JointValues commandedTorque; + bool has_externalTorque; + JointValues externalTorque; + size_t readIORequest_count; + FriIOValue readIORequest[10]; + bool has_timestamp; + TimeStamp timestamp; +} MessageMonitorData; + +typedef struct _Transformation { + char name[64]; + size_t matrix_count; + double matrix[12]; + bool has_timestamp; + TimeStamp timestamp; +} Transformation; + +typedef struct _FRIMonitoringMessage { + MessageHeader header; + bool has_robotInfo; + RobotInfo robotInfo; + bool has_monitorData; + MessageMonitorData monitorData; + bool has_connectionInfo; + ConnectionInfo connectionInfo; + bool has_ipoData; + MessageIpoData ipoData; + size_t requestedTransformations_count; + Transformation requestedTransformations[5]; + bool has_endOfMessageData; + MessageEndOf endOfMessageData; +} FRIMonitoringMessage; + +typedef struct _MessageCommandData { + bool has_jointPosition; + JointValues jointPosition; + bool has_cartesianWrenchFeedForward; + CartesianVector cartesianWrenchFeedForward; + bool has_jointTorque; + JointValues jointTorque; + size_t commandedTransformations_count; + Transformation commandedTransformations[5]; + size_t writeIORequest_count; + FriIOValue writeIORequest[10]; +} MessageCommandData; + +typedef struct _FRICommandMessage { + MessageHeader header; + bool has_commandData; + MessageCommandData commandData; + bool has_endOfMessageData; + MessageEndOf endOfMessageData; +} FRICommandMessage; + +/* Default values for struct fields */ + +/* Field tags (for use in manual encoding/decoding) */ +#define CartesianVector_element_tag 1 +#define Checksum_crc32_tag 1 +#define ConnectionInfo_sessionState_tag 1 +#define ConnectionInfo_quality_tag 2 +#define ConnectionInfo_sendPeriod_tag 3 +#define ConnectionInfo_receiveMultiplier_tag 4 +#define FriIOValue_name_tag 1 +#define FriIOValue_type_tag 2 +#define FriIOValue_direction_tag 3 +#define FriIOValue_digitalValue_tag 4 +#define FriIOValue_analogValue_tag 5 +#define JointValues_value_tag 1 +#define MessageHeader_messageIdentifier_tag 1 +#define MessageHeader_sequenceCounter_tag 2 +#define MessageHeader_reflectedSequenceCounter_tag 3 +#define RobotInfo_numberOfJoints_tag 1 +#define RobotInfo_safetyState_tag 2 +#define RobotInfo_driveState_tag 5 +#define RobotInfo_operationMode_tag 6 +#define RobotInfo_controlMode_tag 7 +#define TimeStamp_sec_tag 1 +#define TimeStamp_nanosec_tag 2 +#define MessageEndOf_messageLength_tag 1 +#define MessageEndOf_messageChecksum_tag 2 +#define MessageIpoData_jointPosition_tag 1 +#define MessageIpoData_clientCommandMode_tag 10 +#define MessageIpoData_overlayType_tag 11 +#define MessageIpoData_trackingPerformance_tag 12 +#define MessageMonitorData_measuredJointPosition_tag 1 +#define MessageMonitorData_measuredTorque_tag 2 +#define MessageMonitorData_commandedJointPosition_tag 3 +#define MessageMonitorData_commandedTorque_tag 4 +#define MessageMonitorData_externalTorque_tag 5 +#define MessageMonitorData_readIORequest_tag 8 +#define MessageMonitorData_timestamp_tag 15 +#define Transformation_name_tag 1 +#define Transformation_matrix_tag 2 +#define Transformation_timestamp_tag 3 +#define FRIMonitoringMessage_header_tag 1 +#define FRIMonitoringMessage_connectionInfo_tag 4 +#define FRIMonitoringMessage_robotInfo_tag 2 +#define FRIMonitoringMessage_monitorData_tag 3 +#define FRIMonitoringMessage_ipoData_tag 5 +#define FRIMonitoringMessage_requestedTransformations_tag 6 +#define FRIMonitoringMessage_endOfMessageData_tag 15 +#define MessageCommandData_jointPosition_tag 1 +#define MessageCommandData_cartesianWrenchFeedForward_tag 2 +#define MessageCommandData_jointTorque_tag 3 +#define MessageCommandData_commandedTransformations_tag 4 +#define MessageCommandData_writeIORequest_tag 5 +#define FRICommandMessage_header_tag 1 +#define FRICommandMessage_commandData_tag 2 +#define FRICommandMessage_endOfMessageData_tag 15 + +/* Struct field encoding specification for nanopb */ +extern const pb_field_t JointValues_fields[2]; +extern const pb_field_t TimeStamp_fields[3]; +extern const pb_field_t CartesianVector_fields[2]; +extern const pb_field_t Checksum_fields[2]; +extern const pb_field_t Transformation_fields[4]; +extern const pb_field_t FriIOValue_fields[6]; +extern const pb_field_t MessageHeader_fields[4]; +extern const pb_field_t ConnectionInfo_fields[5]; +extern const pb_field_t RobotInfo_fields[6]; +extern const pb_field_t MessageMonitorData_fields[8]; +extern const pb_field_t MessageIpoData_fields[5]; +extern const pb_field_t MessageCommandData_fields[6]; +extern const pb_field_t MessageEndOf_fields[3]; +extern const pb_field_t FRIMonitoringMessage_fields[8]; +extern const pb_field_t FRICommandMessage_fields[4]; + +/* Maximum encoded size of messages (where known) */ +#define TimeStamp_size 12 +#define CartesianVector_size 54 +#define Checksum_size 11 +#define Transformation_size 188 +#define FriIOValue_size 98 +#define MessageHeader_size 18 +#define ConnectionInfo_size 24 +#define MessageEndOf_size 24 + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/fri_client/src/HWIFClientApplication.cpp b/fri_client/src/HWIFClientApplication.cpp new file mode 100644 index 00000000..dd971965 --- /dev/null +++ b/fri_client/src/HWIFClientApplication.cpp @@ -0,0 +1,117 @@ +#include + + +namespace KUKA { + namespace FRI { + + HWIFClientApplication::HWIFClientApplication(IConnection& connection, IClient& client) + : ClientApplication(connection, client){} + + bool HWIFClientApplication::client_app_read() { + if (!_connection.isOpen()) + { + printf("Error: client application is not connected!\n"); + return false; + } + + // ************************************************************************** + // Receive and decode new monitoring message + // ************************************************************************** + size_ = _connection.receive(_data->receiveBuffer, FRI_MONITOR_MSG_MAX_SIZE); + + if (size_ <= 0) + { // TODO: size_ == 0 -> connection closed (maybe go to IDLE instead of stopping?) + printf("Error: failed while trying to receive monitoring message!\n"); + return false; + } + + if (!_data->decoder.decode(_data->receiveBuffer, size_)) + { + return false; + } + + // check message type (so that our wrappers match) + if (_data->expectedMonitorMsgID != _data->monitoringMsg.header.messageIdentifier) + { + printf("Error: incompatible IDs for received message (got: %d expected %d)!\n", + (int)_data->monitoringMsg.header.messageIdentifier, + (int)_data->expectedMonitorMsgID); + return false; + } + + return true; + } + + void HWIFClientApplication::client_app_update() { + // ************************************************************************** + // callbacks + // ************************************************************************** + // reset commmand message before callbacks + _data->resetCommandMessage(); + + // callbacks for robot client + ESessionState currentState = (ESessionState)_data->monitoringMsg.connectionInfo.sessionState; + + if (_data->lastState != currentState) + { + _robotClient->onStateChange(_data->lastState, currentState); + _data->lastState = currentState; + } + + switch (currentState) + { + case MONITORING_WAIT: + case MONITORING_READY: + _robotClient->monitor(); + break; + case COMMANDING_WAIT: + _robotClient->waitForCommand(); + break; + case COMMANDING_ACTIVE: + _robotClient->command(); + break; + case IDLE: + default: + return; // nothing to send back + } + + // callback for transformation client + if(_trafoClient != NULL) + { + _trafoClient->provide(); + } + } + + + bool HWIFClientApplication::client_app_write() { + // ************************************************************************** + // Encode and send command message + // ************************************************************************** + + _data->lastSendCounter++; + // check if its time to send an answer + if (_data->lastSendCounter >= _data->monitoringMsg.connectionInfo.receiveMultiplier) + { + _data->lastSendCounter = 0; + + // set sequence counters + _data->commandMsg.header.sequenceCounter = _data->sequenceCounter++; + _data->commandMsg.header.reflectedSequenceCounter = + _data->monitoringMsg.header.sequenceCounter; + + if (!_data->encoder.encode(_data->sendBuffer, size_)) + { + return false; + } + + if (!_connection.send(_data->sendBuffer, size_)) + { + printf("Error: failed while trying to send command message!\n"); + return false; + } + } + + return true; + } + } +} // namespace KUKA::FRI diff --git a/fri_client/src/friClientApplication.cpp b/fri_client/src/friClientApplication.cpp new file mode 100644 index 00000000..62c0842b --- /dev/null +++ b/fri_client/src/friClientApplication.cpp @@ -0,0 +1,211 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#include +#include +#include +#include +#include + +using namespace KUKA::FRI; + +//****************************************************************************** +ClientApplication::ClientApplication(IConnection& connection, IClient& client) + : _connection(connection), _robotClient(&client),_trafoClient(NULL), _data(NULL) +{ + _data = _robotClient->createData(); +} + +//****************************************************************************** +ClientApplication::ClientApplication(IConnection& connection, IClient& client, TransformationClient& trafoClient) + : _connection(connection), _robotClient(&client),_trafoClient(&trafoClient), _data(NULL) +{ + _data = _robotClient->createData(); + _trafoClient->linkData(_data); +} + +//****************************************************************************** +ClientApplication::~ClientApplication() +{ + disconnect(); + delete _data; +} + +//****************************************************************************** +bool ClientApplication::connect(int port, const char *remoteHost) +{ + if (_connection.isOpen()) + { + printf("Warning: client application already connected!\n"); + return true; + } + + return _connection.open(port, remoteHost); +} + +//****************************************************************************** +void ClientApplication::disconnect() +{ + if (_connection.isOpen()) _connection.close(); +} + +//****************************************************************************** +bool ClientApplication::step() +{ + if (!_connection.isOpen()) + { + printf("Error: client application is not connected!\n"); + return false; + } + + // ************************************************************************** + // Receive and decode new monitoring message + // ************************************************************************** + int size = _connection.receive(_data->receiveBuffer, FRI_MONITOR_MSG_MAX_SIZE); + + if (size <= 0) + { // TODO: size == 0 -> connection closed (maybe go to IDLE instead of stopping?) + printf("Error: failed while trying to receive monitoring message!\n"); + return false; + } + + if (!_data->decoder.decode(_data->receiveBuffer, size)) + { + return false; + } + + // check message type (so that our wrappers match) + if (_data->expectedMonitorMsgID != _data->monitoringMsg.header.messageIdentifier) + { + printf("Error: incompatible IDs for received message (got: %d expected %d)!\n", + (int)_data->monitoringMsg.header.messageIdentifier, + (int)_data->expectedMonitorMsgID); + return false; + } + + // ************************************************************************** + // callbacks + // ************************************************************************** + // reset commmand message before callbacks + _data->resetCommandMessage(); + + // callbacks for robot client + ESessionState currentState = (ESessionState)_data->monitoringMsg.connectionInfo.sessionState; + + if (_data->lastState != currentState) + { + _robotClient->onStateChange(_data->lastState, currentState); + _data->lastState = currentState; + } + + switch (currentState) + { + case MONITORING_WAIT: + case MONITORING_READY: + _robotClient->monitor(); + break; + case COMMANDING_WAIT: + _robotClient->waitForCommand(); + break; + case COMMANDING_ACTIVE: + _robotClient->command(); + break; + case IDLE: + default: + return true; // nothing to send back + } + + // callback for transformation client + if(_trafoClient != NULL) + { + _trafoClient->provide(); + } + + // ************************************************************************** + // Encode and send command message + // ************************************************************************** + + _data->lastSendCounter++; + // check if its time to send an answer + if (_data->lastSendCounter >= _data->monitoringMsg.connectionInfo.receiveMultiplier) + { + _data->lastSendCounter = 0; + + // set sequence counters + _data->commandMsg.header.sequenceCounter = _data->sequenceCounter++; + _data->commandMsg.header.reflectedSequenceCounter = + _data->monitoringMsg.header.sequenceCounter; + + if (!_data->encoder.encode(_data->sendBuffer, size)) + { + return false; + } + + if (!_connection.send(_data->sendBuffer, size)) + { + printf("Error: failed while trying to send command message!\n"); + return false; + } + } + + return true; +} + diff --git a/fri_client/src/friClientData.h b/fri_client/src/friClientData.h new file mode 100644 index 00000000..452f74dd --- /dev/null +++ b/fri_client/src/friClientData.h @@ -0,0 +1,240 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_CLIENT_DATA_H +#define _KUKA_FRI_CLIENT_DATA_H + +#include + +#include +#include +#include +#include +#include + +namespace KUKA +{ +namespace FRI +{ + + struct ClientData + { + char receiveBuffer[FRI_MONITOR_MSG_MAX_SIZE];//!< monitoring message receive buffer + char sendBuffer[FRI_COMMAND_MSG_MAX_SIZE]; //!< command message send buffer + + FRIMonitoringMessage monitoringMsg; //!< monitoring message struct + FRICommandMessage commandMsg; //!< command message struct + + MonitoringMessageDecoder decoder; //!< monitoring message decoder + CommandMessageEncoder encoder; //!< command message encoder + + ESessionState lastState; //!< last FRI state + uint32_t sequenceCounter; //!< sequence counter for command messages + uint32_t lastSendCounter; //!< steps since last send command + uint32_t expectedMonitorMsgID; //!< expected ID for received monitoring messages + + const size_t MAX_REQUESTED_TRANSFORMATIONS; //!< maximum count of requested transformations + const size_t MAX_SIZE_TRANSFORMATION_ID; //!< maximum size in bytes of a transformation ID + std::vector requestedTrafoIDs; //!< list of requested transformation ids + + ClientData(int numDofs) + : decoder(&monitoringMsg, numDofs), + encoder(&commandMsg, numDofs), + lastState(IDLE), + sequenceCounter(0), + lastSendCounter(0), + expectedMonitorMsgID(0), + MAX_REQUESTED_TRANSFORMATIONS(sizeof(monitoringMsg.requestedTransformations) / + sizeof(monitoringMsg.requestedTransformations[0])), + MAX_SIZE_TRANSFORMATION_ID(sizeof(monitoringMsg.requestedTransformations[0].name)) + { + requestedTrafoIDs.reserve(MAX_REQUESTED_TRANSFORMATIONS); + } + + void resetCommandMessage() + { + commandMsg.commandData.has_jointPosition = false; + commandMsg.commandData.has_cartesianWrenchFeedForward = false; + commandMsg.commandData.has_jointTorque = false; + commandMsg.commandData.commandedTransformations_count = 0; + commandMsg.has_commandData = false; + commandMsg.commandData.writeIORequest_count = 0; + } + + //****************************************************************************** + static const FriIOValue& getBooleanIOValue(const FRIMonitoringMessage* message, const char* name) + { + return getIOValue(message, name, FriIOType_BOOLEAN); + } + + //****************************************************************************** + static const FriIOValue& getDigitalIOValue(const FRIMonitoringMessage* message, const char* name) + { + return getIOValue(message, name, FriIOType_DIGITAL); + } + + //****************************************************************************** + static const FriIOValue& getAnalogIOValue(const FRIMonitoringMessage* message, const char* name) + { + return getIOValue(message, name, FriIOType_ANALOG); + } + + //****************************************************************************** + static void setBooleanIOValue(FRICommandMessage* message, const char* name, const bool value, + const FRIMonitoringMessage* monMessage) + { + setIOValue(message, name, monMessage, FriIOType_BOOLEAN).digitalValue = value; + } + + //****************************************************************************** + static void setDigitalIOValue(FRICommandMessage* message, const char* name, const unsigned long long value, + const FRIMonitoringMessage* monMessage) + { + setIOValue(message, name, monMessage, FriIOType_DIGITAL).digitalValue = value; + } + + //****************************************************************************** + static void setAnalogIOValue(FRICommandMessage* message, const char* name, const double value, + const FRIMonitoringMessage* monMessage) + { + setIOValue(message, name, monMessage, FriIOType_ANALOG).analogValue = value; + } + + protected: + + //****************************************************************************** + static const FriIOValue& getIOValue(const FRIMonitoringMessage* message, const char* name, + const FriIOType ioType) + { + if(message != NULL && message->has_monitorData == true) + { + const MessageMonitorData& monData = message->monitorData; + const bool analogValue = (ioType == FriIOType_ANALOG); + const bool digitalValue = (ioType == FriIOType_DIGITAL | ioType == FriIOType_BOOLEAN); + for(size_t i = 0; i < monData.readIORequest_count; i++) + { + const FriIOValue& ioValue = monData.readIORequest[i]; + if(strcmp(name, ioValue.name) == 0) + { + if(ioValue.type == ioType && + ioValue.has_digitalValue == digitalValue && + ioValue.has_analogValue == analogValue) + { + return ioValue; + } + + const char* ioTypeName; + switch(ioType) + { + case FriIOType_ANALOG: ioTypeName = "analog value"; break; + case FriIOType_DIGITAL: ioTypeName = "digital value"; break; + case FriIOType_BOOLEAN: ioTypeName = "boolean"; break; + default: ioTypeName = "?"; break; + } + + throw FRIException("IO %s is not of type %s.", name, ioTypeName); + } + } + } + + throw FRIException("Could not locate IO %s in monitor message.", name); + } + + //****************************************************************************** + static FriIOValue& setIOValue(FRICommandMessage* message, const char* name, + const FRIMonitoringMessage* monMessage, const FriIOType ioType) + { + MessageCommandData& cmdData = message->commandData; + const size_t maxIOs = sizeof(cmdData.writeIORequest) / sizeof(cmdData.writeIORequest[0]); + if(cmdData.writeIORequest_count < maxIOs) + { + // call getter which will raise an exception if the output doesn't exist + // or is of wrong type. + if(getIOValue(monMessage, name, ioType).direction != FriIODirection_OUTPUT) + { + throw FRIException("IO %s is not an output value.", name); + } + + // add IO value to command message + FriIOValue& ioValue = cmdData.writeIORequest[cmdData.writeIORequest_count]; + + strncpy(ioValue.name, name, sizeof(ioValue.name) - 1); + ioValue.name[sizeof(ioValue.name) - 1] = 0; // ensure termination + ioValue.type = ioType; + ioValue.has_digitalValue = (ioType == FriIOType_DIGITAL | ioType == FriIOType_BOOLEAN); + ioValue.has_analogValue = (ioType == FriIOType_ANALOG); + ioValue.direction = FriIODirection_OUTPUT; + + cmdData.writeIORequest_count ++; + message->has_commandData = true; + + return ioValue; + } + else + { + throw FRIException("Exceeded maximum number of IOs that can be set."); + } + } + }; + +} +} + + +#endif // _KUKA_FRI_CLIENT_DATA_H diff --git a/fri_client/src/friCommandMessageEncoder.cpp b/fri_client/src/friCommandMessageEncoder.cpp new file mode 100644 index 00000000..e6888b72 --- /dev/null +++ b/fri_client/src/friCommandMessageEncoder.cpp @@ -0,0 +1,121 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#include + +using namespace KUKA::FRI; + +//****************************************************************************** +CommandMessageEncoder::CommandMessageEncoder(FRICommandMessage* pMessage, int num) + : m_nNum(num), m_pMessage(pMessage) +{ + initMessage(); +} + +//****************************************************************************** +CommandMessageEncoder::~CommandMessageEncoder() +{ + +} + +//****************************************************************************** +void CommandMessageEncoder::initMessage() +{ + m_pMessage->has_commandData = false; + m_pMessage->has_endOfMessageData = false; + m_pMessage->commandData.has_jointPosition = false; + m_pMessage->commandData.has_cartesianWrenchFeedForward = false; + m_pMessage->commandData.has_jointTorque = false; + m_pMessage->commandData.commandedTransformations_count = 0; + m_pMessage->header.messageIdentifier = 0; + // init with 0. Necessary for creating the correct reflected sequence count in the monitoring msg + m_pMessage->header.sequenceCounter = 0; + m_pMessage->header.reflectedSequenceCounter = 0; + + m_pMessage->commandData.writeIORequest_count = 0; + + // allocate and map memory for protobuf repeated structures + map_repeatedDouble(FRI_MANAGER_NANOPB_ENCODE, m_nNum, + &m_pMessage->commandData.jointPosition.value, + &m_tRecvContainer.jointPosition); + map_repeatedDouble(FRI_MANAGER_NANOPB_ENCODE, m_nNum, + &m_pMessage->commandData.jointTorque.value, + &m_tRecvContainer.jointTorque); + + // nanopb encoding needs to know how many elements the static array contains + // a Cartesian wrench feed forward vector always contains 6 elements + m_pMessage->commandData.cartesianWrenchFeedForward.element_count = 6; +} + +//****************************************************************************** +bool CommandMessageEncoder::encode(char* buffer, int& size) +{ + // generate stream for encoding + pb_ostream_t stream = pb_ostream_from_buffer((uint8_t*)buffer, FRI_COMMAND_MSG_MAX_SIZE); + // encode monitoring Message to stream + bool status = pb_encode(&stream, FRICommandMessage_fields, m_pMessage); + size = stream.bytes_written; + if (!status) + { + printf("!!encoding error: %s!!\n", PB_GET_ERROR(&stream)); + } + return status; +} diff --git a/fri_client/src/friCommandMessageEncoder.h b/fri_client/src/friCommandMessageEncoder.h new file mode 100644 index 00000000..579c2d93 --- /dev/null +++ b/fri_client/src/friCommandMessageEncoder.h @@ -0,0 +1,118 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_COMMANDMESSAGEENCODER_H +#define _KUKA_FRI_COMMANDMESSAGEENCODER_H + + +#include +#include + + + +namespace KUKA +{ +namespace FRI +{ + + static const int FRI_COMMAND_MSG_MAX_SIZE = 1500; //!< max size of a FRI command message + + class CommandMessageEncoder + { + + public: + + CommandMessageEncoder(FRICommandMessage* pMessage, int num); + + ~CommandMessageEncoder(); + + bool encode(char* buffer, int& size); + + private: + + struct LocalCommandDataContainer + { + tRepeatedDoubleArguments jointPosition; + tRepeatedDoubleArguments jointTorque; + + LocalCommandDataContainer() + { + init_repeatedDouble(&jointPosition); + init_repeatedDouble(&jointTorque); + } + + ~LocalCommandDataContainer() + { + free_repeatedDouble(&jointPosition); + free_repeatedDouble(&jointTorque); + } + }; + + int m_nNum; + + LocalCommandDataContainer m_tRecvContainer; + FRICommandMessage* m_pMessage; + + void initMessage(); + }; + +} +} + +#endif // _KUKA_FRI_COMMANDMESSAGEENCODER_H diff --git a/fri_client/src/friLBRClient.cpp b/fri_client/src/friLBRClient.cpp new file mode 100644 index 00000000..7f59df1c --- /dev/null +++ b/fri_client/src/friLBRClient.cpp @@ -0,0 +1,120 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#include + +using namespace KUKA::FRI; +char FRIException::_buffer[1024] = { 0 }; + +//****************************************************************************** +LBRClient::LBRClient() +{ + +} + +//****************************************************************************** +LBRClient::~LBRClient() +{ + +} + +//****************************************************************************** +void LBRClient::onStateChange(ESessionState oldState, ESessionState newState) +{ + // TODO: String converter function for states + printf("LBRiiwaClient state changed from %d to %d\n", oldState, newState); +} + +//****************************************************************************** +void LBRClient::monitor() +{ + robotCommand().setJointPosition(robotState().getCommandedJointPosition()); +} + +//****************************************************************************** +void LBRClient::waitForCommand() +{ + robotCommand().setJointPosition(robotState().getIpoJointPosition()); +} + +//****************************************************************************** +void LBRClient::command() +{ + robotCommand().setJointPosition(robotState().getIpoJointPosition()); +} + +//****************************************************************************** +ClientData* LBRClient::createData() +{ + ClientData* data = new ClientData(_robotState.NUMBER_OF_JOINTS); + + // link monitoring and command message to wrappers + _robotState._message = &data->monitoringMsg; + _robotCommand._cmdMessage = &data->commandMsg; + _robotCommand._monMessage = &data->monitoringMsg; + + // set specific message IDs + data->expectedMonitorMsgID = _robotState.LBRMONITORMESSAGEID; + data->commandMsg.header.messageIdentifier = _robotCommand.LBRCOMMANDMESSAGEID; + + return data; +} + diff --git a/fri_client/src/friLBRCommand.cpp b/fri_client/src/friLBRCommand.cpp new file mode 100644 index 00000000..5f686ca3 --- /dev/null +++ b/fri_client/src/friLBRCommand.cpp @@ -0,0 +1,113 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#include +#include + +using namespace KUKA::FRI; + +//****************************************************************************** +void LBRCommand::setJointPosition(const double* values) +{ + _cmdMessage->has_commandData = true; + _cmdMessage->commandData.has_jointPosition = true; + tRepeatedDoubleArguments *dest = + (tRepeatedDoubleArguments*)_cmdMessage->commandData.jointPosition.value.arg; + memcpy(dest->value, values, LBRState::NUMBER_OF_JOINTS * sizeof(double)); +} + +//****************************************************************************** +void LBRCommand::setWrench(const double* wrench) +{ + _cmdMessage->has_commandData = true; + _cmdMessage->commandData.has_cartesianWrenchFeedForward = true; + + double *dest = _cmdMessage->commandData.cartesianWrenchFeedForward.element; + memcpy(dest, wrench, 6 * sizeof(double)); +} +//****************************************************************************** +void LBRCommand::setTorque(const double* torques) +{ + _cmdMessage->has_commandData = true; + _cmdMessage->commandData.has_jointTorque= true; + + tRepeatedDoubleArguments *dest = + (tRepeatedDoubleArguments*)_cmdMessage->commandData.jointTorque.value.arg; + memcpy(dest->value, torques, LBRState::NUMBER_OF_JOINTS * sizeof(double)); +} + +//****************************************************************************** +void LBRCommand::setBooleanIOValue(const char* name, const bool value) +{ + ClientData::setBooleanIOValue(_cmdMessage, name, value, _monMessage); +} + +//****************************************************************************** +void LBRCommand::setAnalogIOValue(const char* name, const double value) +{ + ClientData::setAnalogIOValue(_cmdMessage, name, value, _monMessage); +} + +//****************************************************************************** +void LBRCommand::setDigitalIOValue(const char* name, const unsigned long long value) +{ + ClientData::setDigitalIOValue(_cmdMessage, name, value, _monMessage); +} diff --git a/fri_client/src/friLBRState.cpp b/fri_client/src/friLBRState.cpp new file mode 100644 index 00000000..9a90c2bc --- /dev/null +++ b/fri_client/src/friLBRState.cpp @@ -0,0 +1,234 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#include + +using namespace KUKA::FRI; + + +LBRState::LBRState():_message(0) +{ + +} +//****************************************************************************** +double LBRState::getSampleTime() const +{ + return _message->connectionInfo.sendPeriod * 0.001; +} + +//****************************************************************************** +ESessionState LBRState::getSessionState() const +{ + return (ESessionState)_message->connectionInfo.sessionState; +} + +//****************************************************************************** +EConnectionQuality LBRState::getConnectionQuality() const +{ + return (EConnectionQuality)_message->connectionInfo.quality; +} + +//****************************************************************************** +ESafetyState LBRState::getSafetyState() const +{ + return (ESafetyState)_message->robotInfo.safetyState; +} + +//****************************************************************************** +EOperationMode LBRState::getOperationMode() const +{ + return (EOperationMode)_message->robotInfo.operationMode; +} + +//****************************************************************************** +EDriveState LBRState::getDriveState() const +{ + tRepeatedIntArguments *values = + (tRepeatedIntArguments *)_message->robotInfo.driveState.arg; + int firstState = (int)values->value[0]; + for (int i=1; ivalue[i]; + if (state != firstState) + { + return TRANSITIONING; + } + } + return (EDriveState)firstState; +} + + +//******************************************************************************** +EOverlayType LBRState::getOverlayType() const +{ + return (EOverlayType)_message->ipoData.overlayType; +} + +//******************************************************************************** +EClientCommandMode LBRState::getClientCommandMode() const +{ + return (EClientCommandMode)_message->ipoData.clientCommandMode; +} + + +//****************************************************************************** +EControlMode LBRState::getControlMode() const +{ + return (EControlMode)_message->robotInfo.controlMode; +} + +//****************************************************************************** +unsigned int LBRState::getTimestampSec() const +{ + return _message->monitorData.timestamp.sec; +} + +//****************************************************************************** +unsigned int LBRState::getTimestampNanoSec() const +{ + return _message->monitorData.timestamp.nanosec; +} + +//****************************************************************************** +const double* LBRState::getMeasuredJointPosition() const +{ + tRepeatedDoubleArguments *values = + (tRepeatedDoubleArguments*)_message->monitorData.measuredJointPosition.value.arg; + return (double*)values->value; +} + +//****************************************************************************** +const double* LBRState::getCommandedJointPosition() const +{ + tRepeatedDoubleArguments *values = + (tRepeatedDoubleArguments*)_message->monitorData.commandedJointPosition.value.arg; + return (double*)values->value; +} + +//****************************************************************************** +const double* LBRState::getMeasuredTorque() const +{ + tRepeatedDoubleArguments *values = + (tRepeatedDoubleArguments*)_message->monitorData.measuredTorque.value.arg; + return (double*)values->value; +} + +//****************************************************************************** +const double* LBRState::getCommandedTorque() const +{ + tRepeatedDoubleArguments *values = + (tRepeatedDoubleArguments*)_message->monitorData.commandedTorque.value.arg; + return (double*)values->value; +} + +//****************************************************************************** +const double* LBRState::getExternalTorque() const +{ + tRepeatedDoubleArguments *values = + (tRepeatedDoubleArguments*)_message->monitorData.externalTorque.value.arg; + return (double*)values->value; +} + +//****************************************************************************** +const double* LBRState::getIpoJointPosition() const +{ + if (!_message->ipoData.has_jointPosition) + { + throw FRIException("IPO joint position not available in monitoring mode."); + return NULL; + } + + tRepeatedDoubleArguments *values = + (tRepeatedDoubleArguments*)_message->ipoData.jointPosition.value.arg; + return (double*)values->value; +} + +//****************************************************************************** +double LBRState::getTrackingPerformance() const +{ + if (!_message->ipoData.has_trackingPerformance) return 0.0; + + return _message->ipoData.trackingPerformance; +} + +//****************************************************************************** +bool LBRState::getBooleanIOValue(const char* name) const +{ + return ClientData::getBooleanIOValue(_message, name).digitalValue != 0; +} + +//****************************************************************************** +unsigned long long LBRState::getDigitalIOValue(const char* name) const +{ + return ClientData::getDigitalIOValue(_message, name).digitalValue; +} + +//****************************************************************************** +double LBRState::getAnalogIOValue(const char* name) const +{ + return ClientData::getAnalogIOValue(_message, name).analogValue; +} + +//****************************************************************************** +/*const std::vector& LBRState::getRequestedIO_IDs() const +{ + return _clientData->getRequestedIO_IDs(); +}*/ diff --git a/fri_client/src/friMonitoringMessageDecoder.cpp b/fri_client/src/friMonitoringMessageDecoder.cpp new file mode 100644 index 00000000..fff80995 --- /dev/null +++ b/fri_client/src/friMonitoringMessageDecoder.cpp @@ -0,0 +1,145 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#include + + +using namespace KUKA::FRI; + +//****************************************************************************** +MonitoringMessageDecoder::MonitoringMessageDecoder(FRIMonitoringMessage* pMessage, int num) + : m_nNum(num), m_pMessage(pMessage) +{ + initMessage(); +} + +//****************************************************************************** +MonitoringMessageDecoder::~MonitoringMessageDecoder() +{ + +} + +//****************************************************************************** +void MonitoringMessageDecoder::initMessage() +{ + // set initial data + // it is assumed that no robot information and monitoring data is available and therefore the + // optional fields are initialized with false + m_pMessage->has_robotInfo = false; + m_pMessage->has_monitorData = false; + m_pMessage->has_connectionInfo = true; + m_pMessage->has_ipoData = false; + m_pMessage->requestedTransformations_count = 0; + m_pMessage->has_endOfMessageData = false; + + + m_pMessage->header.messageIdentifier = 0; + m_pMessage->header.reflectedSequenceCounter = 0; + m_pMessage->header.sequenceCounter = 0; + + m_pMessage->connectionInfo.sessionState = FRISessionState_IDLE; + m_pMessage->connectionInfo.quality = FRIConnectionQuality_POOR; + + m_pMessage->monitorData.readIORequest_count = 0; + + // allocate and map memory for protobuf repeated structures + map_repeatedDouble(FRI_MANAGER_NANOPB_DECODE, m_nNum, + &m_pMessage->monitorData.measuredJointPosition.value, + &m_tSendContainer.m_AxQMsrLocal); + + map_repeatedDouble(FRI_MANAGER_NANOPB_DECODE, m_nNum, + &m_pMessage->monitorData.measuredTorque.value, + &m_tSendContainer.m_AxTauMsrLocal); + + map_repeatedDouble(FRI_MANAGER_NANOPB_DECODE, m_nNum, + &m_pMessage->monitorData.commandedJointPosition.value, + &m_tSendContainer.m_AxQCmdT1mLocal); + + map_repeatedDouble(FRI_MANAGER_NANOPB_DECODE, m_nNum, + &m_pMessage->monitorData.commandedTorque.value, + &m_tSendContainer.m_AxTauCmdLocal); + + map_repeatedDouble(FRI_MANAGER_NANOPB_DECODE, m_nNum, + &m_pMessage->monitorData.externalTorque.value, + &m_tSendContainer.m_AxTauExtMsrLocal); + + map_repeatedDouble(FRI_MANAGER_NANOPB_DECODE,m_nNum, + &m_pMessage->ipoData.jointPosition.value, + &m_tSendContainer.m_AxQCmdIPO); + + map_repeatedInt(FRI_MANAGER_NANOPB_DECODE, m_nNum, + &m_pMessage->robotInfo.driveState, + &m_tSendContainer.m_AxDriveStateLocal); +} + +//****************************************************************************** +bool MonitoringMessageDecoder::decode(char* buffer, int size) +{ + pb_istream_t stream = pb_istream_from_buffer((uint8_t*)buffer, size); + + bool status = pb_decode(&stream, FRIMonitoringMessage_fields, m_pMessage); + if (!status) + { + printf("!!decoding error: %s!!\n", PB_GET_ERROR(&stream)); + } + + return status; +} diff --git a/fri_client/src/friMonitoringMessageDecoder.h b/fri_client/src/friMonitoringMessageDecoder.h new file mode 100644 index 00000000..4b6af5a6 --- /dev/null +++ b/fri_client/src/friMonitoringMessageDecoder.h @@ -0,0 +1,133 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _KUKA_FRI_MONITORINGMESSAGEDECODER_H +#define _KUKA_FRI_MONITORINGMESSAGEDECODER_H + +#include +#include + + +namespace KUKA +{ +namespace FRI +{ + + static const int FRI_MONITOR_MSG_MAX_SIZE = 1500; //!< max size of a FRI monitoring message + + + class MonitoringMessageDecoder + { + + public: + + MonitoringMessageDecoder(FRIMonitoringMessage* pMessage, int num); + + ~MonitoringMessageDecoder(); + + bool decode(char* buffer, int size); + + + private: + + struct LocalMonitoringDataContainer + { + tRepeatedDoubleArguments m_AxQMsrLocal; + tRepeatedDoubleArguments m_AxTauMsrLocal; + tRepeatedDoubleArguments m_AxQCmdT1mLocal; + tRepeatedDoubleArguments m_AxTauCmdLocal; + tRepeatedDoubleArguments m_AxTauExtMsrLocal; + tRepeatedIntArguments m_AxDriveStateLocal; + tRepeatedDoubleArguments m_AxQCmdIPO; + + LocalMonitoringDataContainer() + { + init_repeatedDouble(&m_AxQMsrLocal); + init_repeatedDouble(&m_AxTauMsrLocal); + init_repeatedDouble(&m_AxQCmdT1mLocal); + init_repeatedDouble(&m_AxTauCmdLocal); + init_repeatedDouble(&m_AxTauExtMsrLocal); + init_repeatedDouble(&m_AxQCmdIPO); + init_repeatedInt(&m_AxDriveStateLocal); + } + + ~LocalMonitoringDataContainer() + { + free_repeatedDouble(&m_AxQMsrLocal); + free_repeatedDouble(&m_AxTauMsrLocal); + free_repeatedDouble(&m_AxQCmdT1mLocal); + free_repeatedDouble(&m_AxTauCmdLocal); + free_repeatedDouble(&m_AxTauExtMsrLocal); + free_repeatedDouble(&m_AxQCmdIPO); + free_repeatedInt(&m_AxDriveStateLocal); + } + }; + + int m_nNum; + + LocalMonitoringDataContainer m_tSendContainer; + FRIMonitoringMessage* m_pMessage; + + void initMessage(); + }; + +} +} + +#endif // _KUKA_FRI_MONITORINGMESSAGEDECODER_H diff --git a/fri_client/src/friTransformationClient.cpp b/fri_client/src/friTransformationClient.cpp new file mode 100644 index 00000000..3940a29d --- /dev/null +++ b/fri_client/src/friTransformationClient.cpp @@ -0,0 +1,191 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ + +#include +#include + +#include +#include + +#include +#include + +using namespace KUKA::FRI; + +//****************************************************************************** +TransformationClient::TransformationClient() +{ +} + +//****************************************************************************** +TransformationClient::~TransformationClient() +{ +} + +//****************************************************************************** +const std::vector& TransformationClient::getRequestedTransformationIDs() const +{ + unsigned int trafoCount = _data->monitoringMsg.requestedTransformations_count; + _data->requestedTrafoIDs.resize(trafoCount); + for (unsigned int i=0; irequestedTrafoIDs[i] = _data->monitoringMsg.requestedTransformations[i].name; + } + return _data->requestedTrafoIDs; +} + +//****************************************************************************** +const unsigned int TransformationClient::getTimestampSec() const +{ + return _data->monitoringMsg.monitorData.timestamp.sec; +} + +//****************************************************************************** +const unsigned int TransformationClient::getTimestampNanoSec() const +{ + return _data->monitoringMsg.monitorData.timestamp.nanosec; +} + +//****************************************************************************** +void TransformationClient::setTransformation(const char* transformationID, + const double transformationMatrix[3][4], unsigned int timeSec, unsigned int timeNanoSec) +{ + _data->commandMsg.has_commandData = true; + + unsigned int currentSize = _data->commandMsg.commandData.commandedTransformations_count; + + if (currentSize < _data->MAX_REQUESTED_TRANSFORMATIONS) + { + _data->commandMsg.commandData.commandedTransformations_count++; + Transformation& dest = _data->commandMsg.commandData.commandedTransformations[currentSize]; + strncpy(dest.name, transformationID, _data->MAX_SIZE_TRANSFORMATION_ID); + dest.name[_data->MAX_SIZE_TRANSFORMATION_ID - 1] = '\0'; + dest.matrix_count = 12; + memcpy(dest.matrix, transformationMatrix, 12 * sizeof(double)); + dest.has_timestamp = true; + dest.timestamp.sec = timeSec; + dest.timestamp.nanosec = timeNanoSec; + } + else + { + throw FRIException("Exceeded maximum number of transformations."); + } +} + +//****************************************************************************** +void TransformationClient::linkData(ClientData* clientData) +{ + _data = clientData; +} + +//****************************************************************************** +double TransformationClient::getSampleTime() const +{ + return _data->monitoringMsg.connectionInfo.sendPeriod * 0.001; +} + +//****************************************************************************** +EConnectionQuality TransformationClient::getConnectionQuality() const +{ + return (EConnectionQuality)_data->monitoringMsg.connectionInfo.quality; +} + + +//****************************************************************************** +void TransformationClient::setBooleanIOValue(const char* name, const bool value) +{ + ClientData::setBooleanIOValue(&_data->commandMsg, name, value, &_data->monitoringMsg); +} + +//****************************************************************************** +void TransformationClient::setAnalogIOValue(const char* name, const double value) +{ + ClientData::setAnalogIOValue(&_data->commandMsg, name, value, &_data->monitoringMsg); +} + +//****************************************************************************** +void TransformationClient::setDigitalIOValue(const char* name, const unsigned long long value) +{ + ClientData::setDigitalIOValue(&_data->commandMsg, name, value, &_data->monitoringMsg); +} + +//****************************************************************************** +bool TransformationClient::getBooleanIOValue(const char* name) const +{ + return ClientData::getBooleanIOValue(&_data->monitoringMsg, name).digitalValue != 0; +} + +//****************************************************************************** +unsigned long long TransformationClient::getDigitalIOValue(const char* name) const +{ + return ClientData::getDigitalIOValue(&_data->monitoringMsg, name).digitalValue; +} + +//****************************************************************************** +double TransformationClient::getAnalogIOValue(const char* name) const +{ + return ClientData::getAnalogIOValue(&_data->monitoringMsg, name).analogValue; +} + +//****************************************************************************** +/*const std::vector& TransformationClient::getRequestedIO_IDs() const +{ + return _data->getRequestedIO_IDs(); +}*/ diff --git a/fri_client/src/friUdpConnection.cpp b/fri_client/src/friUdpConnection.cpp new file mode 100644 index 00000000..6558f1d3 --- /dev/null +++ b/fri_client/src/friUdpConnection.cpp @@ -0,0 +1,243 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#include +#include +#ifndef _MSC_VER +#include +#endif + +#include + + +#ifdef WIN32 +#include +#include +#ifdef _MSC_VER +#pragma comment(lib, "ws2_32.lib") +#endif +#endif + +using namespace KUKA::FRI; + +//****************************************************************************** +UdpConnection::UdpConnection(unsigned int receiveTimeout) : + _udpSock(-1), + _receiveTimeout(receiveTimeout) +{ +#ifdef WIN32 + WSADATA WSAData; + WSAStartup(MAKEWORD(2,0), &WSAData); +#endif +} + +//****************************************************************************** +UdpConnection::~UdpConnection() +{ + close(); +#ifdef WIN32 + WSACleanup(); +#endif +} + +//****************************************************************************** +bool UdpConnection::open(int port, const char *controllerAddress) +{ + struct sockaddr_in servAddr; + memset(&servAddr, 0, sizeof(servAddr)); + memset(&_controllerAddr, 0, sizeof(_controllerAddr)); + + // socket creation + _udpSock = socket(PF_INET, SOCK_DGRAM, 0); + if (_udpSock < 0) + { + printf("opening socket failed!\n"); + return false; + } + + // use local server port + servAddr.sin_family = AF_INET; + servAddr.sin_port = htons(port); + servAddr.sin_addr.s_addr = htonl(INADDR_ANY); + + if (bind(_udpSock, (struct sockaddr *)&servAddr, sizeof(servAddr)) < 0) + { + printf("binding port number %d failed!\n", port); + close(); + return false; + } + // initialize the socket properly + _controllerAddr.sin_family = AF_INET; + _controllerAddr.sin_port = htons(port); + if (controllerAddress) + { +#ifndef __MINGW32__ + inet_pton(AF_INET, controllerAddress, &_controllerAddr.sin_addr); +#else + _controllerAddr.sin_addr.s_addr = inet_addr(controllerAddress); +#endif + if ( connect(_udpSock, (struct sockaddr *)&_controllerAddr, sizeof(_controllerAddr)) < 0) + { + printf("connecting to controller with address %s failed !\n", controllerAddress); + close(); + return false; + } + } + else + { + _controllerAddr.sin_addr.s_addr = htonl(INADDR_ANY); + } + return true; +} + +//****************************************************************************** +void UdpConnection::close() +{ + if (isOpen()) + { +#ifdef WIN32 + closesocket(_udpSock); +#else + ::close(_udpSock); +#endif + } + _udpSock = -1; +} + +//****************************************************************************** +bool UdpConnection::isOpen() const +{ + return (_udpSock >= 0); +} + +//****************************************************************************** +int UdpConnection::receive(char *buffer, int maxSize) +{ + if (isOpen()) + { + /** HAVE_SOCKLEN_T + Yes - unbelievable: There are differences in standard calling parameters (types) to recvfrom + Windows winsock, VxWorks and QNX use int + newer Posix (most Linuxes) use socklen_t + */ +#ifdef HAVE_SOCKLEN_T + socklen_t sockAddrSize; +#else + int sockAddrSize; +#endif + sockAddrSize = sizeof(struct sockaddr_in); + /** check for timeout + Because SO_RCVTIMEO is in Windows not correctly implemented, select is used for the receive time out. + If a timeout greater than 0 is given, wait until the timeout is reached or a message was received. + If t, abort the function with an error. + */ + if(_receiveTimeout > 0) + { + + // Set up struct timeval + struct timeval tv; + tv.tv_sec = _receiveTimeout / 1000; + tv.tv_usec = (_receiveTimeout % 1000) * 1000; + + // initialize file descriptor + /** + * Replace FD_ZERO with memset, because bzero is not available for VxWorks + * User Space Aplications(RTPs). Therefore the macro FD_ZERO does not compile. + */ +#ifndef VXWORKS + FD_ZERO(&_filedescriptor); +#else + memset((char *)(&_filedescriptor), 0, sizeof(*(&_filedescriptor))); +#endif + FD_SET(_udpSock, &_filedescriptor); + + // wait until something was received + int numberActiveFileDescr = select(_udpSock+1, &_filedescriptor,NULL,NULL,&tv); + // 0 indicates a timeout + if(numberActiveFileDescr == 0) + { + printf("The connection has timed out. Timeout is %d\n", _receiveTimeout); + return -1; + } + // a negative value indicates an error + else if(numberActiveFileDescr == -1) + { + printf("An error has occured \n"); + return -1; + } + } + + return recvfrom(_udpSock, buffer, maxSize, 0, (struct sockaddr *)&_controllerAddr, &sockAddrSize); + } + return -1; +} + +//****************************************************************************** +bool UdpConnection::send(const char* buffer, int size) +{ + if ((isOpen()) && (ntohs(_controllerAddr.sin_port) != 0)) + { + int sent = sendto(_udpSock, const_cast(buffer), size, 0, (struct sockaddr *)&_controllerAddr, sizeof(_controllerAddr)); + if (sent == size) + { + return true; + } + } + return false; +} diff --git a/fri_client/src/pb_frimessages_callbacks.c b/fri_client/src/pb_frimessages_callbacks.c new file mode 100644 index 00000000..16e29b83 --- /dev/null +++ b/fri_client/src/pb_frimessages_callbacks.c @@ -0,0 +1,267 @@ +/** + + The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + + + \file + \version {1.15} + */ +#include +#include + +#include +#include +#include + +bool encode_repeatedDouble(pb_ostream_t *stream, const pb_field_t *field, void * const *arg) +{ + size_t i = 0; + + tRepeatedDoubleArguments* arguments = 0; + size_t count = 0; + double* values = 0; + + if (arg == NULL || *arg == NULL) + { + return false; + } + arguments = ((tRepeatedDoubleArguments*) (*arg)); + + count = arguments->max_size; + values = arguments->value; + + for (i = 0; i < count; i++) + { + + if (!pb_encode_tag_for_field(stream, field)) + { + return false; + } + + if (!pb_encode_fixed64(stream, &values[i])) + { + return false; + } + } + return true; +} + +bool decode_repeatedDouble(pb_istream_t *stream, const pb_field_t *field, void **arg) +{ + tRepeatedDoubleArguments* arguments = 0; + size_t i = 0; + double* values = 0; + + if (arg == NULL || *arg == NULL) + { + return false; + } + + arguments = (tRepeatedDoubleArguments*) *arg; + i = arguments->size; + values = arguments->value; + + if (values == NULL) + { + return true; + } + + if (!pb_decode_fixed64(stream, &values[i])) + { + return false; + } + + arguments->size++; + if (arguments->size >= arguments->max_size) + { + arguments->size = 0; + } + return true; +} + +bool encode_repeatedInt(pb_ostream_t *stream, const pb_field_t *field, void * const *arg) +{ + int i = 0; + tRepeatedIntArguments* arguments = 0; + int count = 0; + int64_t* values = 0; + + if (arg == NULL || *arg == NULL) + { + return false; + } + arguments = (tRepeatedIntArguments*) *arg; + count = arguments->max_size; + values = arguments->value; + for (i = 0; i < count; i++) + { + + if (!pb_encode_tag_for_field(stream, field)) + { + return false; + } + if (!pb_encode_varint(stream, values[i])) + { + return false; + } + } + return true; +} + +bool decode_repeatedInt(pb_istream_t *stream, const pb_field_t *field, void **arg) +{ + tRepeatedIntArguments* arguments = 0; + size_t i = 0; + uint64_t* values = 0; + + if (arg == NULL || *arg == NULL) + { + return false; + } + arguments = (tRepeatedIntArguments*) *arg; + + i = arguments->size; + values = (uint64_t*) arguments->value; + if (values == NULL) + { + return true; + } + + if (!pb_decode_varint(stream, &values[i])) + { + return false; + } + + arguments->size++; + if (arguments->size >= arguments->max_size) + { + arguments->size = 0; + } + return true; +} + +void map_repeatedDouble(eNanopbCallbackDirection dir, int numDOF, pb_callback_t *values, tRepeatedDoubleArguments *arg) +{ + // IMPORTANT: the callbacks are stored in a union, therefor a message object + // must be exclusive defined for transmission or reception + if (dir == FRI_MANAGER_NANOPB_ENCODE) + { + values->funcs.encode = &encode_repeatedDouble; + } + else + { + values->funcs.decode = &decode_repeatedDouble; + } + // map the local container data to the message data fields + arg->max_size = numDOF; + arg->size = 0; + if (numDOF > 0) + { + arg->value = (double*) malloc(numDOF * sizeof(double)); + + } + values->arg = arg; +} + +void map_repeatedInt(eNanopbCallbackDirection dir, int numDOF, pb_callback_t *values, tRepeatedIntArguments *arg) +{ + // IMPORTANT: the callbacks are stored in a union, therefor a message object + // must be exclusive defined for transmission or reception + if (dir == FRI_MANAGER_NANOPB_ENCODE) + { + // set the encode callback function + values->funcs.encode = &encode_repeatedInt; + } + else + { + // set the decode callback function + values->funcs.decode = &decode_repeatedInt; + } + // map the robot drive state from the container to message field + arg->max_size = numDOF; + arg->size = 0; + if (numDOF > 0) + { + arg->value = (int64_t*) malloc(numDOF * sizeof(int64_t)); + + } + values->arg = arg; +} + +void init_repeatedDouble(tRepeatedDoubleArguments *arg) +{ + arg->size = 0; + arg->max_size = 0; + arg->value = NULL; +} + +void init_repeatedInt(tRepeatedIntArguments *arg) +{ + arg->size = 0; + arg->max_size = 0; + arg->value = NULL; +} + +void free_repeatedDouble(tRepeatedDoubleArguments *arg) +{ + if (arg->value != NULL) + free(arg->value); +} + +void free_repeatedInt(tRepeatedIntArguments *arg) +{ + if (arg->value != NULL) + free(arg->value); +} diff --git a/fri_client/src/pb_frimessages_callbacks.h b/fri_client/src/pb_frimessages_callbacks.h new file mode 100644 index 00000000..f31526c3 --- /dev/null +++ b/fri_client/src/pb_frimessages_callbacks.h @@ -0,0 +1,121 @@ +/** + +The following license terms and conditions apply, unless a redistribution +agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. + +SCOPE + +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source +code, libraries, binaries, manuals and technical documentation. + +COPYRIGHT + +All Rights Reserved +Copyright (C) 2014-2019 +KUKA Roboter GmbH +Augsburg, Germany + +LICENSE + +Redistribution and use of the software in source and binary forms, with or +without modification, are permitted provided that the following conditions are +met: +a) The software is used in conjunction with KUKA products only. +b) Redistributions of source code must retain the above copyright notice, this +list of conditions and the disclaimer. +c) Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the disclaimer in the documentation and/or other +materials provided with the distribution. Altered source code of the +redistribution must be made available upon request with the distribution. +d) Modification and contributions to the original software provided by KUKA +must be clearly marked and the authorship must be stated. +e) Neither the name of KUKA nor the trademarks owned by KUKA may be used to +endorse or promote products derived from this software without specific prior +written permission. + +DISCLAIMER OF WARRANTY + +The Software is provided "AS IS" and "WITH ALL FAULTS," without warranty of +any kind, including without limitation the warranties of merchantability, +fitness for a particular purpose and non-infringement. +KUKA makes no warranty that the Software is free of defects or is suitable for +any particular purpose. In no event shall KUKA be responsible for loss or +damages arising from the installation or use of the Software, including but +not limited to any indirect, punitive, special, incidental or consequential +damages of any character including, without limitation, damages for loss of +goodwill, work stoppage, computer failure or malfunction, or any and all other +commercial damages or losses. +The entire risk to the quality and performance of the Software is not borne by +KUKA. Should the Software prove defective, KUKA is not liable for the entire +cost of any service and repair. + + + +\file +\version {1.15} +*/ +#ifndef _pb_frimessages_callbacks_H +#define _pb_frimessages_callbacks_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +/** container for repeated double elements */ +typedef struct repeatedDoubleArguments { + size_t size; + size_t max_size; + double* value; +} tRepeatedDoubleArguments; + +/** container for repeated integer elements */ +typedef struct repeatedIntArguments { + size_t size; + size_t max_size; + int64_t* value; +} tRepeatedIntArguments; + +/** enumeration for direction (encoding/decoding) */ +typedef enum DIRECTION { + FRI_MANAGER_NANOPB_DECODE = 0, //!< Argument um eine + FRI_MANAGER_NANOPB_ENCODE = 1 //!< +} eNanopbCallbackDirection; + + +bool encode_repeatedDouble(pb_ostream_t *stream, const pb_field_t *field, + void * const *arg); + +bool decode_repeatedDouble(pb_istream_t *stream, const pb_field_t *field, + void **arg); + +bool encode_repeatedInt(pb_ostream_t *stream, const pb_field_t *field, + void * const *arg); + +bool decode_repeatedInt(pb_istream_t *stream, const pb_field_t *field, + void **arg); + +void map_repeatedDouble(eNanopbCallbackDirection dir, int numDOF, + pb_callback_t *values, tRepeatedDoubleArguments *arg); + +void map_repeatedInt(eNanopbCallbackDirection dir, int numDOF, + pb_callback_t *values, tRepeatedIntArguments *arg); + +void init_repeatedDouble(tRepeatedDoubleArguments *arg); + +void init_repeatedInt(tRepeatedIntArguments *arg); + +void free_repeatedDouble(tRepeatedDoubleArguments *arg); + +void free_repeatedInt(tRepeatedIntArguments *arg); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/fri_client/third_party/nanopb/.gitignore b/fri_client/third_party/nanopb/.gitignore new file mode 100644 index 00000000..c0df4621 --- /dev/null +++ b/fri_client/third_party/nanopb/.gitignore @@ -0,0 +1,2 @@ +### build +build diff --git a/fri_client/third_party/nanopb/CHANGELOG.txt b/fri_client/third_party/nanopb/CHANGELOG.txt new file mode 100644 index 00000000..e35ee3ab --- /dev/null +++ b/fri_client/third_party/nanopb/CHANGELOG.txt @@ -0,0 +1,150 @@ +nanopb-0.2.8 (2014-05-20) + Fix security issue with PB_ENABLE_MALLOC. (issue 117) + Add option to not add timestamps to .pb.h and .pb.c preambles. (issue 115) + Documentation updates + Improved tests + +nanopb-0.2.7 (2014-04-07) + Fix bug with default values for extension fields (issue 111) + Fix some MISRA-C warnings (issue 91) + Implemented optional malloc() support (issue 80) + Changed pointer-type bytes field datatype + Add a "found" field to pb_extension_t (issue 112) + Add convenience function pb_get_encoded_size() (issue 16) + +nanopb-0.2.6 (2014-02-15) + Fix generator error with bytes callback fields (issue 99) + Fix warnings about large integer constants (issue 102) + Add comments to where STATIC_ASSERT is used (issue 96) + Add warning about unknown field names on .options (issue 105) + Move descriptor.proto to google/protobuf subdirectory (issue 104) + Improved tests + +nanopb-0.2.5 (2014-01-01) + Fix a bug with encoding negative values in int32 fields (issue 97) + Create binary packages of the generator + dependencies (issue 47) + Add support for pointer-type fields to the encoder (part of issue 80) + Fixed path in FindNanopb.cmake (issue 94) + Improved tests + +nanopb-0.2.4 (2013-11-07) + Remove the deprecated NANOPB_INTERNALS functions from public API. + Document the security model. + Check array and bytes max sizes when encoding (issue 90) + Add #defines for maximum encoded message size (issue 89) + Add #define tags for extension fields (issue 93) + Fix MISRA C violations (issue 91) + Clean up pb_field_t definition with typedefs. + +nanopb-0.2.3 (2013-09-18) + Improve compatibility by removing ternary operator from initializations (issue 88) + Fix build error on Visual C++ (issue 84, patch by Markus Schwarzenberg) + Don't stop on unsupported extension fields (issue 83) + Add an example pb_syshdr.h file for non-C99 compilers + Reorganize tests and examples into subfolders (issue 63) + Switch from Makefiles to scons for building the tests + Make the tests buildable on Windows + +nanopb-0.2.2 (2013-08-18) + Add support for extension fields (issue 17) + Fix unknown fields in empty message (issue 78) + Include the field tags in the generated .pb.h file. + Add pb_decode_delimited and pb_encode_delimited wrapper functions (issue 74) + Add a section in top of pb.h for changing compilation settings (issue 76) + Documentation improvements (issues 12, 77 and others) + Improved tests + +nanopb-0.2.1 (2013-04-14) + NOTE: The default callback function signature has changed. + If you don't want to update your code, define PB_OLD_CALLBACK_STYLE. + + Change the callback function to use void** (issue 69) + Add support for defining the nanopb options in a separate file (issue 12) + Add support for packed structs in IAR and MSVC (in addition to GCC) (issue 66) + Implement error message support for the encoder side (issue 7) + Handle unterminated strings when encoding (issue 68) + Fix bug with empty strings in repeated string callbacks (issue 73) + Fix regression in 0.2.0 with optional callback fields (issue 70) + Fix bugs with empty message types (issues 64, 65) + Fix some compiler warnings on clang (issue 67) + Some portability improvements (issues 60, 62) + Various new generator options + Improved tests + +nanopb-0.2.0 (2013-03-02) + NOTE: This release requires you to regenerate all .pb.c + files. Files generated by older versions will not + compile anymore. + + Reformat generated .pb.c files using macros (issue 58) + Rename PB_HTYPE_ARRAY -> PB_HTYPE_REPEATED + Separate PB_HTYPE to PB_ATYPE and PB_HTYPE + Move STATIC_ASSERTs to .pb.c file + Added CMake file (by Pavel Ilin) + Add option to give file extension to generator (by Michael Haberler) + Documentation updates + +nanopb-0.1.9 (2013-02-13) + Fixed error message bugs (issues 52, 56) + Sanitize #ifndef filename (issue 50) + Performance improvements + Add compile-time option PB_BUFFER_ONLY + Add Java package name to nanopb.proto + Check for sizeof(double) == 8 (issue 54) + Added generator option to ignore some fields. (issue 51) + Added generator option to make message structs packed. (issue 49) + Add more test cases. + +nanopb-0.1.8 (2012-12-13) + Fix bugs in the enum short names introduced in 0.1.7 (issues 42, 43) + Fix STATIC_ASSERT macro when using multiple .proto files. (issue 41) + Fix missing initialization of istream.errmsg + Make tests/Makefile work for non-gcc compilers (issue 40) + +nanopb-0.1.7 (2012-11-11) + Remove "skip" mode from pb_istream_t callbacks. Example implementation had a bug. (issue 37) + Add option to use shorter names for enum values (issue 38) + Improve options support in generator (issues 12, 30) + Add nanopb version number to generated files (issue 36) + Add extern "C" to generated headers (issue 35) + Add names for structs to allow forward declaration (issue 39) + Add buffer size check in example (issue 34) + Fix build warnings on MS compilers (issue 33) + +nanopb-0.1.6 (2012-09-02) + Reorganize the field decoder interface (issue 2) + Improve performance in submessage decoding (issue 28) + Implement error messages in the decoder side (issue 7) + Extended testcases (alltypes test is now complete). + Fix some compiler warnings (issues 25, 26, 27, 32). + +nanopb-0.1.5 (2012-08-04) + Fix bug in decoder with packed arrays (issue 23). + Extended testcases. + Fix some compiler warnings. + +nanopb-0.1.4 (2012-07-05) + Add compile-time options for easy-to-use >255 field support. + Improve the detection of missing required fields. + Added example on how to handle union messages. + Fix generator error with .proto without messages. + Fix problems that stopped the code from compiling with some compilers. + Fix some compiler warnings. + +nanopb-0.1.3 (2012-06-12) + Refactor the field encoder interface. + Improve generator error messages (issue 5) + Add descriptor.proto into the #include exclusion list + Fix some compiler warnings. + +nanopb-0.1.2 (2012-02-15) + Make the generator to generate include for other .proto files (issue 4). + Fixed generator not working on Windows (issue 3) + +nanopb-0.1.1 (2012-01-14) + Fixed bug in encoder with 'bytes' fields (issue 1). + Fixed a bug in the generator that caused a compiler error on sfixed32 and sfixed64 fields. + Extended testcases. + +nanopb-0.1.0 (2012-01-06) + First stable release. diff --git a/fri_client/third_party/nanopb/CMakeLists.txt b/fri_client/third_party/nanopb/CMakeLists.txt new file mode 100644 index 00000000..fd4a64de --- /dev/null +++ b/fri_client/third_party/nanopb/CMakeLists.txt @@ -0,0 +1,103 @@ +cmake_minimum_required(VERSION 3.1...3.15) + +### CMake support for the nanopb library - protocol buffers for embedded systems +if(${CMAKE_VERSION} VERSION_LESS 3.12) + cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) +endif() + +project(NanoPB VERSION 0.2.8 + DESCRIPTION "Nanopb - Protocol Buffers for Embedded Systems." + LANGUAGES C +) + +### Append CMAKE_MODULE_PATH by custom find file +list(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_SOURCE_DIR}/cmake) + +### Add the nanopb library +add_library(nanopb + src/pb_decode.c + src/pb_encode.c +) + +### Add compile options, similar to https://stackoverflow.com/questions/45955272/modern-way-to-set-compiler-flags-in-cross-platform-cmake-project +if(MSVC) + target_compile_options(nanopb + PRIVATE + -DPB_SYSTEM_HEADER= + -DPB_FIELD_16BIT + -DWIN32 + -DHAVE_STDINT_H + -DHAVE_STDBOOL_H + ) +else() + target_compile_options(nanopb + PRIVATE + -O2 + -Wall + -DHAVE_SOCKLEN_T + -DPB_SYSTEM_HEADER= + -DPB_FIELD_16BIT + -DHAVE_STDINT_H + -DHAVE_STDDEF_H + -DHAVE_STDBOOL_H + -DHAVE_STDLIB_H + -DHAVE_STRING_H + ) +endif() + +### Create an alias so that one can link against this library inside build tree +add_library(NanoPB::nanopb ALIAS nanopb) + +### Set target properties +target_include_directories(nanopb + PUBLIC + $ + $ +) + +### Install instructions +include(GNUInstallDirs) +set(INSTALL_CONFIGDIR ${CMAKE_INSTALL_LIBDIR}/cmake/nanopb) + +install(TARGETS nanopb + EXPORT nanopb-targets + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} +) + +### Set exported target's name to NanoPB +set_target_properties(nanopb PROPERTIES EXPORT_NAME NanoPB) +install(DIRECTORY include/ DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}) + +### Export target to a script +install(EXPORT nanopb-targets + FILE NanoPBTargets.cmake + NAMESPACE NanoPB:: + DESTINATION ${INSTALL_CONFIGDIR} +) + +### Create a ConfigVersion.cmake file +include(CMakePackageConfigHelpers) +write_basic_package_version_file( + ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfigVersion.cmake + VERSION ${PROJECT_VERSION} + COMPATIBILITY AnyNewerVersion +) + +configure_package_config_file(${CMAKE_CURRENT_LIST_DIR}/cmake/NanoPBConfig.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfig.cmake + INSTALL_DESTINATION ${INSTALL_CONFIGDIR} +) + +### Install the config, configversion and custom find modules +install(FILES + ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfig.cmake + ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfigVersion.cmake + DESTINATION ${INSTALL_CONFIGDIR} +) + +### Export target from the build tree +export(EXPORT nanopb-targets FILE ${CMAKE_CURRENT_BINARY_DIR}/NanoPBTargets.cmake NAMESPACE NanoPB) + +### Register package in user's package registry +export(PACKAGE NanoPB) \ No newline at end of file diff --git a/fri_client/third_party/nanopb/LICENSE.txt b/fri_client/third_party/nanopb/LICENSE.txt new file mode 100644 index 00000000..d11c9af1 --- /dev/null +++ b/fri_client/third_party/nanopb/LICENSE.txt @@ -0,0 +1,20 @@ +Copyright (c) 2011 Petteri Aimonen + +This software is provided 'as-is', without any express or +implied warranty. In no event will the authors be held liable +for any damages arising from the use of this software. + +Permission is granted to anyone to use this software for any +purpose, including commercial applications, and to alter it and +redistribute it freely, subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you + must not claim that you wrote the original software. If you use + this software in a product, an acknowledgment in the product + documentation would be appreciated but is not required. + +2. Altered source versions must be plainly marked as such, and + must not be misrepresented as being the original software. + +3. This notice may not be removed or altered from any source + distribution. diff --git a/fri_client/third_party/nanopb/README.txt b/fri_client/third_party/nanopb/README.txt new file mode 100644 index 00000000..0f2ade8b --- /dev/null +++ b/fri_client/third_party/nanopb/README.txt @@ -0,0 +1,61 @@ +Nanopb is a small code-size Protocol Buffers implementation in ansi C. It is +especially suitable for use in microcontrollers, but fits any memory +restricted system. + +Homepage: http://kapsi.fi/~jpa/nanopb/ + + + + +Using the nanopb library +======================== +To use the nanopb library, you need to do two things: + +1) Compile your .proto files for nanopb, using protoc. +2) Include pb_encode.c and pb_decode.c in your project. + +The easiest way to get started is to study the project in "examples/simple". +It contains a Makefile, which should work directly under most Linux systems. +However, for any other kind of build system, see the manual steps in +README.txt in that folder. + + + +Using the Protocol Buffers compiler (protoc) +============================================ +The nanopb generator is implemented as a plugin for the Google's own protoc +compiler. This has the advantage that there is no need to reimplement the +basic parsing of .proto files. However, it does mean that you need the +Google's protobuf library in order to run the generator. + +If you have downloaded a binary package for nanopb (either Windows, Linux or +Mac OS X version), the 'protoc' binary is included in the 'generator-bin' +folder. In this case, you are ready to go. Simply run this command: + + generator-bin/protoc --nanopb_out=. myprotocol.proto + +However, if you are using a git checkout or a plain source distribution, you +need to provide your own version of protoc and the Google's protobuf library. +On Linux, the necessary packages are protobuf-compiler and python-protobuf. +On Windows, you can either build Google's protobuf library from source or use +one of the binary distributions of it. In either case, if you use a separate +protoc, you need to manually give the path to nanopb generator: + + protoc --plugin=protoc-gen-nanopb=nanopb/generator/protoc-gen-nanopb ... + + + +Running the tests +================= +If you want to perform further development of the nanopb core, or to verify +its functionality using your compiler and platform, you'll want to run the +test suite. The build rules for the test suite are implemented using Scons, +so you need to have that installed. To run the tests: + + cd tests + scons + +This will show the progress of various test cases. If the output does not +end in an error, the test cases were successful. + + diff --git a/fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in b/fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in new file mode 100644 index 00000000..245eb7c0 --- /dev/null +++ b/fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in @@ -0,0 +1,10 @@ +get_filename_component(NanoPB_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) +include(CMakeFindDependencyMacro) + +list(APPEND CMAKE_MODULE_PATH ${NanoPB_CMAKE_DIR}) + +if(NOT TARGET NanoPB::NanoPB) + include("${NanoPB_CMAKE_DIR}/NanoPBTargets.cmake") +endif() + +set(NanoPB_LIBRARIES NanoPB::NanoPB) \ No newline at end of file diff --git a/fri_client/third_party/nanopb/include/nanopb/pb.h b/fri_client/third_party/nanopb/include/nanopb/pb.h new file mode 100644 index 00000000..258ec925 --- /dev/null +++ b/fri_client/third_party/nanopb/include/nanopb/pb.h @@ -0,0 +1,519 @@ +/* Common parts of the nanopb library. Most of these are quite low-level + * stuff. For the high-level interface, see pb_encode.h and pb_decode.h. + */ + +#ifndef _PB_H_ +#define _PB_H_ + +/***************************************************************** + * Nanopb compilation time options. You can change these here by * + * uncommenting the lines, or on the compiler command line. * + *****************************************************************/ + +/* Enable support for dynamically allocated fields */ +/* #define PB_ENABLE_MALLOC 1 */ + +/* Define this if your CPU architecture is big endian, i.e. it + * stores the most-significant byte first. */ +/* #define __BIG_ENDIAN__ 1 */ + +/* Increase the number of required fields that are tracked. + * A compiler warning will tell if you need this. */ +/* #define PB_MAX_REQUIRED_FIELDS 256 */ + +/* Add support for tag numbers > 255 and fields larger than 255 bytes. */ +/* #define PB_FIELD_16BIT 1 */ + +/* Add support for tag numbers > 65536 and fields larger than 65536 bytes. */ +/* #define PB_FIELD_32BIT 1 */ + +/* Disable support for error messages in order to save some code space. */ +/* #define PB_NO_ERRMSG 1 */ + +/* Disable support for custom streams (support only memory buffers). */ +/* #define PB_BUFFER_ONLY 1 */ + +/* Switch back to the old-style callback function signature. + * This was the default until nanopb-0.2.1. */ +/* #define PB_OLD_CALLBACK_STYLE */ + + +/****************************************************************** + * You usually don't need to change anything below this line. * + * Feel free to look around and use the defined macros, though. * + ******************************************************************/ + + +/* Version of the nanopb library. Just in case you want to check it in + * your own program. */ +#define NANOPB_VERSION nanopb-0.2.8 + +/* Include all the system headers needed by nanopb. You will need the + * definitions of the following: + * - strlen, memcpy, memset functions + * - [u]int8_t, [u]int16_t, [u]int32_t, [u]int64_t + * - size_t + * - bool + * + * If you don't have the standard header files, you can instead provide + * a custom header that defines or includes all this. In that case, + * define PB_SYSTEM_HEADER to the path of this file. + */ +#ifdef PB_SYSTEM_HEADER +#include PB_SYSTEM_HEADER +#else +#include +#include +#include +#include + +#ifdef PB_ENABLE_MALLOC +#include +#endif +#endif + +/* Macro for defining packed structures (compiler dependent). + * This just reduces memory requirements, but is not required. + */ +#if defined(__GNUC__) || defined(__clang__) + /* For GCC and clang */ +# define PB_PACKED_STRUCT_START +# define PB_PACKED_STRUCT_END +# define pb_packed __attribute__((packed)) +#elif defined(__ICCARM__) + /* For IAR ARM compiler */ +# define PB_PACKED_STRUCT_START _Pragma("pack(push, 1)") +# define PB_PACKED_STRUCT_END _Pragma("pack(pop)") +# define pb_packed +#elif defined(_MSC_VER) && (_MSC_VER >= 1500) + /* For Microsoft Visual C++ */ +# define PB_PACKED_STRUCT_START __pragma(pack(push, 1)) +# define PB_PACKED_STRUCT_END __pragma(pack(pop)) +# define pb_packed +#else + /* Unknown compiler */ +# define PB_PACKED_STRUCT_START +# define PB_PACKED_STRUCT_END +# define pb_packed +#endif + +/* Handly macro for suppressing unreferenced-parameter compiler warnings. */ +#ifndef UNUSED +#define UNUSED(x) (void)(x) +#endif + +/* Compile-time assertion, used for checking compatible compilation options. + * If this does not work properly on your compiler, use #define STATIC_ASSERT + * to disable it. + * + * But before doing that, check carefully the error message / place where it + * comes from to see if the error has a real cause. Unfortunately the error + * message is not always very clear to read, but you can see the reason better + * in the place where the STATIC_ASSERT macro was called. + */ +#ifndef STATIC_ASSERT +#define STATIC_ASSERT(COND,MSG) typedef char STATIC_ASSERT_MSG(MSG, __LINE__, __COUNTER__)[(COND)?1:-1]; +#define STATIC_ASSERT_MSG(MSG, LINE, COUNTER) STATIC_ASSERT_MSG_(MSG, LINE, COUNTER) +#define STATIC_ASSERT_MSG_(MSG, LINE, COUNTER) static_assertion_##MSG##LINE##COUNTER +#endif + +/* Number of required fields to keep track of. */ +#ifndef PB_MAX_REQUIRED_FIELDS +#define PB_MAX_REQUIRED_FIELDS 64 +#endif + +#if PB_MAX_REQUIRED_FIELDS < 64 +#error You should not lower PB_MAX_REQUIRED_FIELDS from the default value (64). +#endif + +/* List of possible field types. These are used in the autogenerated code. + * Least-significant 4 bits tell the scalar type + * Most-significant 4 bits specify repeated/required/packed etc. + */ + +typedef uint8_t pb_type_t; + +/**** Field data types ****/ + +/* Numeric types */ +#define PB_LTYPE_VARINT 0x00 /* int32, int64, enum, bool */ +#define PB_LTYPE_UVARINT 0x01 /* uint32, uint64 */ +#define PB_LTYPE_SVARINT 0x02 /* sint32, sint64 */ +#define PB_LTYPE_FIXED32 0x03 /* fixed32, sfixed32, float */ +#define PB_LTYPE_FIXED64 0x04 /* fixed64, sfixed64, double */ + +/* Marker for last packable field type. */ +#define PB_LTYPE_LAST_PACKABLE 0x04 + +/* Byte array with pre-allocated buffer. + * data_size is the length of the allocated PB_BYTES_ARRAY structure. */ +#define PB_LTYPE_BYTES 0x05 + +/* String with pre-allocated buffer. + * data_size is the maximum length. */ +#define PB_LTYPE_STRING 0x06 + +/* Submessage + * submsg_fields is pointer to field descriptions */ +#define PB_LTYPE_SUBMESSAGE 0x07 + +/* Extension pseudo-field + * The field contains a pointer to pb_extension_t */ +#define PB_LTYPE_EXTENSION 0x08 + +/* Number of declared LTYPES */ +#define PB_LTYPES_COUNT 9 +#define PB_LTYPE_MASK 0x0F + +/**** Field repetition rules ****/ + +#define PB_HTYPE_REQUIRED 0x00 +#define PB_HTYPE_OPTIONAL 0x10 +#define PB_HTYPE_REPEATED 0x20 +#define PB_HTYPE_MASK 0x30 + +/**** Field allocation types ****/ + +#define PB_ATYPE_STATIC 0x00 +#define PB_ATYPE_POINTER 0x80 +#define PB_ATYPE_CALLBACK 0x40 +#define PB_ATYPE_MASK 0xC0 + +#define PB_ATYPE(x) ((x) & PB_ATYPE_MASK) +#define PB_HTYPE(x) ((x) & PB_HTYPE_MASK) +#define PB_LTYPE(x) ((x) & PB_LTYPE_MASK) + +/* Data type used for storing sizes of struct fields + * and array counts. + */ +#if defined(PB_FIELD_32BIT) + typedef uint32_t pb_size_t; + typedef int32_t pb_ssize_t; +#elif defined(PB_FIELD_16BIT) + typedef uint16_t pb_size_t; + typedef int16_t pb_ssize_t; +#else + typedef uint8_t pb_size_t; + typedef int8_t pb_ssize_t; +#endif + +/* This structure is used in auto-generated constants + * to specify struct fields. + * You can change field sizes if you need structures + * larger than 256 bytes or field tags larger than 256. + * The compiler should complain if your .proto has such + * structures. Fix that by defining PB_FIELD_16BIT or + * PB_FIELD_32BIT. + */ +PB_PACKED_STRUCT_START +typedef struct _pb_field_t pb_field_t; +struct _pb_field_t { + pb_size_t tag; + pb_type_t type; + pb_size_t data_offset; /* Offset of field data, relative to previous field. */ + pb_ssize_t size_offset; /* Offset of array size or has-boolean, relative to data */ + pb_size_t data_size; /* Data size in bytes for a single item */ + pb_size_t array_size; /* Maximum number of entries in array */ + + /* Field definitions for submessage + * OR default value for all other non-array, non-callback types + * If null, then field will zeroed. */ + const void *ptr; +} pb_packed; +PB_PACKED_STRUCT_END + +/* Make sure that the standard integer types are of the expected sizes. + * All kinds of things may break otherwise.. atleast all fixed* types. + * + * If you get errors here, it probably means that your stdint.h is not + * correct for your platform. + */ +STATIC_ASSERT(sizeof(int8_t) == 1, INT8_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(uint8_t) == 1, UINT8_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(int16_t) == 2, INT16_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(uint16_t) == 2, UINT16_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(int32_t) == 4, INT32_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(uint32_t) == 4, UINT32_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(int64_t) == 8, INT64_T_WRONG_SIZE) +STATIC_ASSERT(sizeof(uint64_t) == 8, UINT64_T_WRONG_SIZE) + +/* This structure is used for 'bytes' arrays. + * It has the number of bytes in the beginning, and after that an array. + * Note that actual structs used will have a different length of bytes array. + */ +#define PB_BYTES_ARRAY_T(n) struct { size_t size; uint8_t bytes[n]; } +#define PB_BYTES_ARRAY_T_ALLOCSIZE(n) ((size_t)n + offsetof(pb_bytes_array_t, bytes)) + +struct _pb_bytes_array_t { + size_t size; + uint8_t bytes[1]; +}; +typedef struct _pb_bytes_array_t pb_bytes_array_t; + +/* This structure is used for giving the callback function. + * It is stored in the message structure and filled in by the method that + * calls pb_decode. + * + * The decoding callback will be given a limited-length stream + * If the wire type was string, the length is the length of the string. + * If the wire type was a varint/fixed32/fixed64, the length is the length + * of the actual value. + * The function may be called multiple times (especially for repeated types, + * but also otherwise if the message happens to contain the field multiple + * times.) + * + * The encoding callback will receive the actual output stream. + * It should write all the data in one call, including the field tag and + * wire type. It can write multiple fields. + * + * The callback can be null if you want to skip a field. + */ +typedef struct _pb_istream_t pb_istream_t; +typedef struct _pb_ostream_t pb_ostream_t; +typedef struct _pb_callback_t pb_callback_t; +struct _pb_callback_t { +#ifdef PB_OLD_CALLBACK_STYLE + /* Deprecated since nanopb-0.2.1 */ + union { + bool (*decode)(pb_istream_t *stream, const pb_field_t *field, void *arg); + bool (*encode)(pb_ostream_t *stream, const pb_field_t *field, const void *arg); + } funcs; +#else + /* New function signature, which allows modifying arg contents in callback. */ + union { + bool (*decode)(pb_istream_t *stream, const pb_field_t *field, void **arg); + bool (*encode)(pb_ostream_t *stream, const pb_field_t *field, void * const *arg); + } funcs; +#endif + + /* Free arg for use by callback */ + void *arg; +}; + +/* Wire types. Library user needs these only in encoder callbacks. */ +typedef enum { + PB_WT_VARINT = 0, + PB_WT_64BIT = 1, + PB_WT_STRING = 2, + PB_WT_32BIT = 5 +} pb_wire_type_t; + +/* Structure for defining the handling of unknown/extension fields. + * Usually the pb_extension_type_t structure is automatically generated, + * while the pb_extension_t structure is created by the user. However, + * if you want to catch all unknown fields, you can also create a custom + * pb_extension_type_t with your own callback. + */ +typedef struct _pb_extension_type_t pb_extension_type_t; +typedef struct _pb_extension_t pb_extension_t; +struct _pb_extension_type_t { + /* Called for each unknown field in the message. + * If you handle the field, read off all of its data and return true. + * If you do not handle the field, do not read anything and return true. + * If you run into an error, return false. + * Set to NULL for default handler. + */ + bool (*decode)(pb_istream_t *stream, pb_extension_t *extension, + uint32_t tag, pb_wire_type_t wire_type); + + /* Called once after all regular fields have been encoded. + * If you have something to write, do so and return true. + * If you do not have anything to write, just return true. + * If you run into an error, return false. + * Set to NULL for default handler. + */ + bool (*encode)(pb_ostream_t *stream, const pb_extension_t *extension); + + /* Free field for use by the callback. */ + const void *arg; +}; + +struct _pb_extension_t { + /* Type describing the extension field. Usually you'll initialize + * this to a pointer to the automatically generated structure. */ + const pb_extension_type_t *type; + + /* Destination for the decoded data. This must match the datatype + * of the extension field. */ + void *dest; + + /* Pointer to the next extension handler, or NULL. + * If this extension does not match a field, the next handler is + * automatically called. */ + pb_extension_t *next; + + /* The decoder sets this to true if the extension was found. + * Ignored for encoding. */ + bool found; +}; + +/* Memory allocation functions to use. You can define pb_realloc and + * pb_free to custom functions if you want. */ +#ifdef PB_ENABLE_MALLOC +# ifndef pb_realloc +# define pb_realloc(ptr, size) realloc(ptr, size) +# endif +# ifndef pb_free +# define pb_free(ptr) free(ptr) +# endif +#endif + +/* These macros are used to declare pb_field_t's in the constant array. */ +/* Size of a structure member, in bytes. */ +#define pb_membersize(st, m) (sizeof ((st*)0)->m) +/* Number of entries in an array. */ +#define pb_arraysize(st, m) (pb_membersize(st, m) / pb_membersize(st, m[0])) +/* Delta from start of one member to the start of another member. */ +#define pb_delta(st, m1, m2) ((int)offsetof(st, m1) - (int)offsetof(st, m2)) +/* Marks the end of the field list */ +#define PB_LAST_FIELD {0,(pb_type_t) 0,0,0,0,0,0} + +/* Macros for filling in the data_offset field */ +/* data_offset for first field in a message */ +#define PB_DATAOFFSET_FIRST(st, m1, m2) (offsetof(st, m1)) +/* data_offset for subsequent fields */ +#define PB_DATAOFFSET_OTHER(st, m1, m2) (offsetof(st, m1) - offsetof(st, m2) - pb_membersize(st, m2)) +/* Choose first/other based on m1 == m2 (deprecated, remains for backwards compatibility) */ +#define PB_DATAOFFSET_CHOOSE(st, m1, m2) (int)(offsetof(st, m1) == offsetof(st, m2) \ + ? PB_DATAOFFSET_FIRST(st, m1, m2) \ + : PB_DATAOFFSET_OTHER(st, m1, m2)) + +/* Required fields are the simplest. They just have delta (padding) from + * previous field end, and the size of the field. Pointer is used for + * submessages and default values. + */ +#define PB_REQUIRED_STATIC(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_STATIC | PB_HTYPE_REQUIRED | ltype, \ + fd, 0, pb_membersize(st, m), 0, ptr} + +/* Optional fields add the delta to the has_ variable. */ +#define PB_OPTIONAL_STATIC(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_STATIC | PB_HTYPE_OPTIONAL | ltype, \ + fd, \ + pb_delta(st, has_ ## m, m), \ + pb_membersize(st, m), 0, ptr} + +/* Repeated fields have a _count field and also the maximum number of entries. */ +#define PB_REPEATED_STATIC(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_STATIC | PB_HTYPE_REPEATED | ltype, \ + fd, \ + pb_delta(st, m ## _count, m), \ + pb_membersize(st, m[0]), \ + pb_arraysize(st, m), ptr} + +/* Allocated fields carry the size of the actual data, not the pointer */ +#define PB_REQUIRED_POINTER(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_POINTER | PB_HTYPE_REQUIRED | ltype, \ + fd, 0, pb_membersize(st, m[0]), 0, ptr} + +/* Optional fields don't need a has_ variable, as information would be redundant */ +#define PB_OPTIONAL_POINTER(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_POINTER | PB_HTYPE_OPTIONAL | ltype, \ + fd, 0, pb_membersize(st, m[0]), 0, ptr} + +/* Repeated fields have a _count field and a pointer to array of pointers */ +#define PB_REPEATED_POINTER(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_POINTER | PB_HTYPE_REPEATED | ltype, \ + fd, pb_delta(st, m ## _count, m), \ + pb_membersize(st, m[0]), 0, ptr} + +/* Callbacks are much like required fields except with special datatype. */ +#define PB_REQUIRED_CALLBACK(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_CALLBACK | PB_HTYPE_REQUIRED | ltype, \ + fd, 0, pb_membersize(st, m), 0, ptr} + +#define PB_OPTIONAL_CALLBACK(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_CALLBACK | PB_HTYPE_OPTIONAL | ltype, \ + fd, 0, pb_membersize(st, m), 0, ptr} + +#define PB_REPEATED_CALLBACK(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_CALLBACK | PB_HTYPE_REPEATED | ltype, \ + fd, 0, pb_membersize(st, m), 0, ptr} + +/* Optional extensions don't have the has_ field, as that would be redundant. */ +#define PB_OPTEXT_STATIC(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_STATIC | PB_HTYPE_OPTIONAL | ltype, \ + 0, \ + 0, \ + pb_membersize(st, m), 0, ptr} + +#define PB_OPTEXT_CALLBACK(tag, st, m, fd, ltype, ptr) \ + {tag, PB_ATYPE_CALLBACK | PB_HTYPE_OPTIONAL | ltype, \ + 0, 0, pb_membersize(st, m), 0, ptr} + +/* The mapping from protobuf types to LTYPEs is done using these macros. */ +#define PB_LTYPE_MAP_BOOL PB_LTYPE_VARINT +#define PB_LTYPE_MAP_BYTES PB_LTYPE_BYTES +#define PB_LTYPE_MAP_DOUBLE PB_LTYPE_FIXED64 +#define PB_LTYPE_MAP_ENUM PB_LTYPE_VARINT +#define PB_LTYPE_MAP_FIXED32 PB_LTYPE_FIXED32 +#define PB_LTYPE_MAP_FIXED64 PB_LTYPE_FIXED64 +#define PB_LTYPE_MAP_FLOAT PB_LTYPE_FIXED32 +#define PB_LTYPE_MAP_INT32 PB_LTYPE_VARINT +#define PB_LTYPE_MAP_INT64 PB_LTYPE_VARINT +#define PB_LTYPE_MAP_MESSAGE PB_LTYPE_SUBMESSAGE +#define PB_LTYPE_MAP_SFIXED32 PB_LTYPE_FIXED32 +#define PB_LTYPE_MAP_SFIXED64 PB_LTYPE_FIXED64 +#define PB_LTYPE_MAP_SINT32 PB_LTYPE_SVARINT +#define PB_LTYPE_MAP_SINT64 PB_LTYPE_SVARINT +#define PB_LTYPE_MAP_STRING PB_LTYPE_STRING +#define PB_LTYPE_MAP_UINT32 PB_LTYPE_UVARINT +#define PB_LTYPE_MAP_UINT64 PB_LTYPE_UVARINT +#define PB_LTYPE_MAP_EXTENSION PB_LTYPE_EXTENSION + +/* This is the actual macro used in field descriptions. + * It takes these arguments: + * - Field tag number + * - Field type: BOOL, BYTES, DOUBLE, ENUM, FIXED32, FIXED64, + * FLOAT, INT32, INT64, MESSAGE, SFIXED32, SFIXED64 + * SINT32, SINT64, STRING, UINT32, UINT64 or EXTENSION + * - Field rules: REQUIRED, OPTIONAL or REPEATED + * - Allocation: STATIC or CALLBACK + * - Message name + * - Field name + * - Previous field name (or field name again for first field) + * - Pointer to default value or submsg fields. + */ + +#define PB_FIELD(tag, type, rules, allocation, message, field, prevfield, ptr) \ + PB_ ## rules ## _ ## allocation(tag, message, field, \ + PB_DATAOFFSET_CHOOSE(message, field, prevfield), \ + PB_LTYPE_MAP_ ## type, ptr) + +/* This is a new version of the macro used by nanopb generator from + * version 0.2.3 onwards. It avoids the use of a ternary expression in + * the initialization, which confused some compilers. + * + * - Placement: FIRST or OTHER, depending on if this is the first field in structure. + * + */ +#define PB_FIELD2(tag, type, rules, allocation, placement, message, field, prevfield, ptr) \ + PB_ ## rules ## _ ## allocation(tag, message, field, \ + PB_DATAOFFSET_ ## placement(message, field, prevfield), \ + PB_LTYPE_MAP_ ## type, ptr) + + +/* These macros are used for giving out error messages. + * They are mostly a debugging aid; the main error information + * is the true/false return value from functions. + * Some code space can be saved by disabling the error + * messages if not used. + */ +#ifdef PB_NO_ERRMSG +#define PB_RETURN_ERROR(stream,msg) \ + do {\ + UNUSED(stream); \ + return false; \ + } while(0) +#define PB_GET_ERROR(stream) "(errmsg disabled)" +#else +#define PB_RETURN_ERROR(stream,msg) \ + do {\ + if ((stream)->errmsg == NULL) \ + (stream)->errmsg = (msg); \ + return false; \ + } while(0) +#define PB_GET_ERROR(stream) ((stream)->errmsg ? (stream)->errmsg : "(none)") +#endif + +#endif diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_decode.h b/fri_client/third_party/nanopb/include/nanopb/pb_decode.h new file mode 100644 index 00000000..75ca119f --- /dev/null +++ b/fri_client/third_party/nanopb/include/nanopb/pb_decode.h @@ -0,0 +1,149 @@ +/* pb_decode.h: Functions to decode protocol buffers. Depends on pb_decode.c. + * The main function is pb_decode. You also need an input stream, and the + * field descriptions created by nanopb_generator.py. + */ + +#ifndef _PB_DECODE_H_ +#define _PB_DECODE_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* Structure for defining custom input streams. You will need to provide + * a callback function to read the bytes from your storage, which can be + * for example a file or a network socket. + * + * The callback must conform to these rules: + * + * 1) Return false on IO errors. This will cause decoding to abort. + * 2) You can use state to store your own data (e.g. buffer pointer), + * and rely on pb_read to verify that no-body reads past bytes_left. + * 3) Your callback may be used with substreams, in which case bytes_left + * is different than from the main stream. Don't use bytes_left to compute + * any pointers. + */ +struct _pb_istream_t +{ +#ifdef PB_BUFFER_ONLY + /* Callback pointer is not used in buffer-only configuration. + * Having an int pointer here allows binary compatibility but + * gives an error if someone tries to assign callback function. + */ + int *callback; +#else + bool (*callback)(pb_istream_t *stream, uint8_t *buf, size_t count); +#endif + + void *state; /* Free field for use by callback implementation */ + size_t bytes_left; + +#ifndef PB_NO_ERRMSG + const char *errmsg; +#endif +}; + +/*************************** + * Main decoding functions * + ***************************/ + +/* Decode a single protocol buffers message from input stream into a C structure. + * Returns true on success, false on any failure. + * The actual struct pointed to by dest must match the description in fields. + * Callback fields of the destination structure must be initialized by caller. + * All other fields will be initialized by this function. + * + * Example usage: + * MyMessage msg = {}; + * uint8_t buffer[64]; + * pb_istream_t stream; + * + * // ... read some data into buffer ... + * + * stream = pb_istream_from_buffer(buffer, count); + * pb_decode(&stream, MyMessage_fields, &msg); + */ +bool pb_decode(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct); + +/* Same as pb_decode, except does not initialize the destination structure + * to default values. This is slightly faster if you need no default values + * and just do memset(struct, 0, sizeof(struct)) yourself. + * + * This can also be used for 'merging' two messages, i.e. update only the + * fields that exist in the new message. + * + * Note: If this function returns with an error, it will not release any + * dynamically allocated fields. You will need to call pb_release() yourself. + */ +bool pb_decode_noinit(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct); + +/* Same as pb_decode, except expects the stream to start with the message size + * encoded as varint. Corresponds to parseDelimitedFrom() in Google's + * protobuf API. + */ +bool pb_decode_delimited(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct); + +#ifdef PB_ENABLE_MALLOC +/* Release any allocated pointer fields. If you use dynamic allocation, you should + * call this for any successfully decoded message when you are done with it. If + * pb_decode() returns with an error, the message is already released. + */ +void pb_release(const pb_field_t fields[], void *dest_struct); +#endif + + +/************************************** + * Functions for manipulating streams * + **************************************/ + +/* Create an input stream for reading from a memory buffer. + * + * Alternatively, you can use a custom stream that reads directly from e.g. + * a file or a network socket. + */ +pb_istream_t pb_istream_from_buffer(uint8_t *buf, size_t bufsize); + +/* Function to read from a pb_istream_t. You can use this if you need to + * read some custom header data, or to read data in field callbacks. + */ +bool pb_read(pb_istream_t *stream, uint8_t *buf, size_t count); + + +/************************************************ + * Helper functions for writing field callbacks * + ************************************************/ + +/* Decode the tag for the next field in the stream. Gives the wire type and + * field tag. At end of the message, returns false and sets eof to true. */ +bool pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, uint32_t *tag, bool *eof); + +/* Skip the field payload data, given the wire type. */ +bool pb_skip_field(pb_istream_t *stream, pb_wire_type_t wire_type); + +/* Decode an integer in the varint format. This works for bool, enum, int32, + * int64, uint32 and uint64 field types. */ +bool pb_decode_varint(pb_istream_t *stream, uint64_t *dest); + +/* Decode an integer in the zig-zagged svarint format. This works for sint32 + * and sint64. */ +bool pb_decode_svarint(pb_istream_t *stream, int64_t *dest); + +/* Decode a fixed32, sfixed32 or float value. You need to pass a pointer to + * a 4-byte wide C variable. */ +bool pb_decode_fixed32(pb_istream_t *stream, void *dest); + +/* Decode a fixed64, sfixed64 or double value. You need to pass a pointer to + * a 8-byte wide C variable. */ +bool pb_decode_fixed64(pb_istream_t *stream, void *dest); + +/* Make a limited-length substream for reading a PB_WT_STRING field. */ +bool pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream); +void pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_encode.h b/fri_client/third_party/nanopb/include/nanopb/pb_encode.h new file mode 100644 index 00000000..8c7b32c9 --- /dev/null +++ b/fri_client/third_party/nanopb/include/nanopb/pb_encode.h @@ -0,0 +1,154 @@ +/* pb_encode.h: Functions to encode protocol buffers. Depends on pb_encode.c. + * The main function is pb_encode. You also need an output stream, and the + * field descriptions created by nanopb_generator.py. + */ + +#ifndef _PB_ENCODE_H_ +#define _PB_ENCODE_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* Structure for defining custom output streams. You will need to provide + * a callback function to write the bytes to your storage, which can be + * for example a file or a network socket. + * + * The callback must conform to these rules: + * + * 1) Return false on IO errors. This will cause encoding to abort. + * 2) You can use state to store your own data (e.g. buffer pointer). + * 3) pb_write will update bytes_written after your callback runs. + * 4) Substreams will modify max_size and bytes_written. Don't use them + * to calculate any pointers. + */ +struct _pb_ostream_t +{ +#ifdef PB_BUFFER_ONLY + /* Callback pointer is not used in buffer-only configuration. + * Having an int pointer here allows binary compatibility but + * gives an error if someone tries to assign callback function. + * Also, NULL pointer marks a 'sizing stream' that does not + * write anything. + */ + int *callback; +#else + bool (*callback)(pb_ostream_t *stream, const uint8_t *buf, size_t count); +#endif + void *state; /* Free field for use by callback implementation. */ + size_t max_size; /* Limit number of output bytes written (or use SIZE_MAX). */ + size_t bytes_written; /* Number of bytes written so far. */ + +#ifndef PB_NO_ERRMSG + const char *errmsg; +#endif +}; + +/*************************** + * Main encoding functions * + ***************************/ + +/* Encode a single protocol buffers message from C structure into a stream. + * Returns true on success, false on any failure. + * The actual struct pointed to by src_struct must match the description in fields. + * All required fields in the struct are assumed to have been filled in. + * + * Example usage: + * MyMessage msg = {}; + * uint8_t buffer[64]; + * pb_ostream_t stream; + * + * msg.field1 = 42; + * stream = pb_ostream_from_buffer(buffer, sizeof(buffer)); + * pb_encode(&stream, MyMessage_fields, &msg); + */ +bool pb_encode(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct); + +/* Same as pb_encode, but prepends the length of the message as a varint. + * Corresponds to writeDelimitedTo() in Google's protobuf API. + */ +bool pb_encode_delimited(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct); + +/* Encode the message to get the size of the encoded data, but do not store + * the data. */ +bool pb_get_encoded_size(size_t *size, const pb_field_t fields[], const void *src_struct); + +/************************************** + * Functions for manipulating streams * + **************************************/ + +/* Create an output stream for writing into a memory buffer. + * The number of bytes written can be found in stream.bytes_written after + * encoding the message. + * + * Alternatively, you can use a custom stream that writes directly to e.g. + * a file or a network socket. + */ +pb_ostream_t pb_ostream_from_buffer(uint8_t *buf, size_t bufsize); + +/* Pseudo-stream for measuring the size of a message without actually storing + * the encoded data. + * + * Example usage: + * MyMessage msg = {}; + * pb_ostream_t stream = PB_OSTREAM_SIZING; + * pb_encode(&stream, MyMessage_fields, &msg); + * printf("Message size is %d\n", stream.bytes_written); + */ +#ifndef PB_NO_ERRMSG +#define PB_OSTREAM_SIZING {0,0,0,0,0} +#else +#define PB_OSTREAM_SIZING {0,0,0,0} +#endif + +/* Function to write into a pb_ostream_t stream. You can use this if you need + * to append or prepend some custom headers to the message. + */ +bool pb_write(pb_ostream_t *stream, const uint8_t *buf, size_t count); + + +/************************************************ + * Helper functions for writing field callbacks * + ************************************************/ + +/* Encode field header based on type and field number defined in the field + * structure. Call this from the callback before writing out field contents. */ +bool pb_encode_tag_for_field(pb_ostream_t *stream, const pb_field_t *field); + +/* Encode field header by manually specifing wire type. You need to use this + * if you want to write out packed arrays from a callback field. */ +bool pb_encode_tag(pb_ostream_t *stream, pb_wire_type_t wiretype, uint32_t field_number); + +/* Encode an integer in the varint format. + * This works for bool, enum, int32, int64, uint32 and uint64 field types. */ +bool pb_encode_varint(pb_ostream_t *stream, uint64_t value); + +/* Encode an integer in the zig-zagged svarint format. + * This works for sint32 and sint64. */ +bool pb_encode_svarint(pb_ostream_t *stream, int64_t value); + +/* Encode a string or bytes type field. For strings, pass strlen(s) as size. */ +bool pb_encode_string(pb_ostream_t *stream, const uint8_t *buffer, size_t size); + +/* Encode a fixed32, sfixed32 or float value. + * You need to pass a pointer to a 4-byte wide C variable. */ +bool pb_encode_fixed32(pb_ostream_t *stream, const void *value); + +/* Encode a fixed64, sfixed64 or double value. + * You need to pass a pointer to a 8-byte wide C variable. */ +bool pb_encode_fixed64(pb_ostream_t *stream, const void *value); + +/* Encode a submessage field. + * You need to pass the pb_field_t array and pointer to struct, just like + * with pb_encode(). This internally encodes the submessage twice, first to + * calculate message size and then to actually write it out. + */ +bool pb_encode_submessage(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h b/fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h new file mode 100644 index 00000000..d437000c --- /dev/null +++ b/fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h @@ -0,0 +1,127 @@ +/* This is an example of a header file for platforms/compilers that do + * not come with stdint.h/stddef.h/stdbool.h/string.h. To use it, define + * PB_SYSTEM_HEADER as "pb_syshdr.h", including the quotes, and add the + * extra folder to your include path. + * + * It is very likely that you will need to customize this file to suit + * your platform. For any compiler that supports C99, this file should + * not be necessary. + * + * KUKA: Added VXWORKS support + */ + +#ifndef _PB_SYSHDR_H_ +#define _PB_SYSHDR_H_ + +/* KUKA VxWorks 6.8 support */ +#ifdef VXWORKS + #define HAVE_STRING_H + #define HAVE_STDLIB_H +#ifdef _WRS_KERNEL + #include // int32_t, int64_t, ... + #define HAVE_STDINT_H_ALTERNATIVE + #define HAVE_STDDEF_H_ALTERNATIVE +#else + #define HAVE_STDINT_H + #define HAVE_STDDEF_H +#endif // _WRS_KERNEL +#endif // VXWORKS + +/* KUKA: size_t is defined in stddef.h, stdlib.h or string.h */ +#if !defined(HAVE_STDDEF_H) && !defined(HAVE_STDLIB_H) && !defined(HAVE_STRING_H) +typedef uint32_t size_t; +#endif + + + +/* stdint.h subset */ +#ifdef HAVE_STDINT_H +#include +#else +#ifndef HAVE_STDINT_H_ALTERNATIVE +/* You will need to modify these to match the word size of your platform. */ +typedef signed char int8_t; +typedef unsigned char uint8_t; +typedef signed short int16_t; +typedef unsigned short uint16_t; +typedef signed int int32_t; +typedef unsigned int uint32_t; +typedef signed long long int64_t; +typedef unsigned long long uint64_t; +#endif // HAVE_STDINT_H_ALTERNATIVE +#endif // HAVE_STDINT_H + +/* stddef.h subset */ +#ifdef HAVE_STDDEF_H +#include +#else +#ifndef HAVE_STDDEF_H_ALTERNATIVE +#define offsetof(st, m) ((size_t)(&((st *)0)->m)) +#ifndef NULL +#define NULL 0 +#endif // NULL +#endif // HAVE_STDDEF_H_ALTERNATIVE +#endif // HAVE_STDDEF_H + +/* stdbool.h subset */ +#ifdef HAVE_STDBOOL_H +#include +#else + +#ifndef __cplusplus +typedef int bool; +#define false 0 +#define true 1 +#endif + +#endif // HAVE_STDBOOL_H + +/* stdlib.h subset */ +#ifdef PB_ENABLE_MALLOC +#ifdef HAVE_STDLIB_H +#include +#else +void *realloc(void *ptr, size_t size); +void free(void *ptr); +#endif // HAVE_STDLIB_H +#endif // PB_ENABLE_MALLOC + +/* string.h subset */ +#ifdef HAVE_STRING_H +#include +#else + +/* Implementations are from the Public Domain C Library (PDCLib). */ +static size_t strlen( const char * s ) +{ + size_t rc = 0; + while ( s[rc] ) + { + ++rc; + } + return rc; +} + +static void * memcpy( void *s1, const void *s2, size_t n ) +{ + char * dest = (char *) s1; + const char * src = (const char *) s2; + while ( n-- ) + { + *dest++ = *src++; + } + return s1; +} + +static void * memset( void * s, int c, size_t n ) +{ + unsigned char * p = (unsigned char *) s; + while ( n-- ) + { + *p++ = (unsigned char) c; + } + return s; +} +#endif // HAVE_STRING_H + +#endif // _PB_SYSHDR_H_ diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h b/fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h new file mode 100644 index 00000000..73bbb64f --- /dev/null +++ b/fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h @@ -0,0 +1,119 @@ +/* This is a headerfile customized for Microsoft Visual Studio 2010 + * - based on example of a header file for platforms/compilers that do + * not come with stdint.h/stddef.h/stdbool.h/string.h. To use it, define + * PB_SYSTEM_HEADER as "pb_syshdr_win.h", including the quotes, and add the + * extra folder to your include path. + * + * Authorship: This file was altered/created by KUKA Roboter GmbH, Augsburg, Germany in 2014 + * + */ + +#ifndef _PB_SYSHDR_WIN_H_ +#define _PB_SYSHDR_WIN_H_ + +/* stdint.h subset */ +#ifdef HAVE_STDINT_H +#include +#else +/* You will need to modify these to match the word size of your platform. */ +typedef signed char int8_t; +typedef unsigned char uint8_t; +typedef signed short int16_t; +typedef unsigned short uint16_t; +typedef signed int int32_t; +typedef unsigned int uint32_t; +typedef signed long long int64_t; +typedef unsigned long long uint64_t; + +// from stdint.h +#define INT8_MAX 0x7f +#define INT16_MAX 0x7fff +#define INT32_MAX 0x7fffffff +#define UINT8_MAX 0xffU +#define UINT16_MAX 0xffffU +#define UINT32_MAX 0xffffffffU +#endif + +/* stddef.h subset */ +#ifdef HAVE_STDDEF_H +#include +#else + +//typedef uint32_t size_t; // wird dieser typedef wirklich benötigt?!? +#ifndef offsetof +#define offsetof(st, m) ((size_t)(&((st *)0)->m)) +#endif + +#ifndef NULL +#define NULL 0 +#endif + +#endif + +/* stdbool.h subset */ +#ifdef HAVE_STDBOOL_H +#include +#else + +#ifndef __cplusplus +typedef int bool; +#define false 0 +#define true 1 +#endif + +#endif + +/* stdlib.h subset */ +#ifdef PB_ENABLE_MALLOC +#ifdef HAVE_STDLIB_H +#include +#else +void *realloc(void *ptr, size_t size); +void free(void *ptr); +#endif +#endif + +/* string.h subset */ +#ifdef HAVE_STRING_H +#include +#else + +#ifndef WIN32 +/* Implementations are from the Public Domain C Library (PDCLib). */ +static size_t strlen( const char * s ) +{ + size_t rc = 0; + while ( s[rc] ) + { + ++rc; + } + return rc; +} + +static void * memcpy( void *s1, const void *s2, size_t n ) +{ + char * dest = (char *) s1; + const char * src = (const char *) s2; + while ( n-- ) + { + *dest++ = *src++; + } + return s1; +} + +static void * memset( void * s, int c, size_t n ) +{ + unsigned char * p = (unsigned char *) s; + while ( n-- ) + { + *p++ = (unsigned char) c; + } + return s; +} +#else +#include +#endif + +#endif + +#endif diff --git a/fri_client/third_party/nanopb/src/pb_decode.c b/fri_client/third_party/nanopb/src/pb_decode.c new file mode 100644 index 00000000..8e34b179 --- /dev/null +++ b/fri_client/third_party/nanopb/src/pb_decode.c @@ -0,0 +1,1198 @@ +/* pb_decode.c -- decode a protobuf using minimal resources + * + * 2011 Petteri Aimonen + */ + +/* Use the GCC warn_unused_result attribute to check that all return values + * are propagated correctly. On other compilers and gcc before 3.4.0 just + * ignore the annotation. + */ +#if !defined(__GNUC__) || ( __GNUC__ < 3) || (__GNUC__ == 3 && __GNUC_MINOR__ < 4) + #define checkreturn +#else + #define checkreturn __attribute__((warn_unused_result)) +#endif + +#include +#include + +/************************************** + * Declarations internal to this file * + **************************************/ + +/* Iterator for pb_field_t list */ +typedef struct { + const pb_field_t *start; /* Start of the pb_field_t array */ + const pb_field_t *pos; /* Current position of the iterator */ + unsigned field_index; /* Zero-based index of the field. */ + unsigned required_field_index; /* Zero-based index that counts only the required fields */ + void *dest_struct; /* Pointer to the destination structure to decode to */ + void *pData; /* Pointer where to store current field value */ + void *pSize; /* Pointer where to store the size of current array field */ +} pb_field_iterator_t; + +typedef bool (*pb_decoder_t)(pb_istream_t *stream, const pb_field_t *field, void *dest) checkreturn; + +static bool checkreturn buf_read(pb_istream_t *stream, uint8_t *buf, size_t count); +static bool checkreturn pb_decode_varint32(pb_istream_t *stream, uint32_t *dest); +static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire_type, uint8_t *buf, size_t *size); +static void pb_field_init(pb_field_iterator_t *iter, const pb_field_t *fields, void *dest_struct); +static bool pb_field_next(pb_field_iterator_t *iter); +static bool checkreturn pb_field_find(pb_field_iterator_t *iter, uint32_t tag); +static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter); +static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter); +static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter); +static bool checkreturn default_extension_decoder(pb_istream_t *stream, pb_extension_t *extension, uint32_t tag, pb_wire_type_t wire_type); +static bool checkreturn decode_extension(pb_istream_t *stream, uint32_t tag, pb_wire_type_t wire_type, pb_field_iterator_t *iter); +static bool checkreturn find_extension_field(pb_field_iterator_t *iter); +static void pb_message_set_to_defaults(const pb_field_t fields[], void *dest_struct); +static bool checkreturn pb_dec_varint(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_uvarint(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_svarint(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_fixed32(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_fixed64(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_t *field, void *dest); +static bool checkreturn pb_skip_varint(pb_istream_t *stream); +static bool checkreturn pb_skip_string(pb_istream_t *stream); + +/* --- Function pointers to field decoders --- + * Order in the array must match pb_action_t LTYPE numbering. + */ +static const pb_decoder_t PB_DECODERS[PB_LTYPES_COUNT] = { + &pb_dec_varint, + &pb_dec_uvarint, + &pb_dec_svarint, + &pb_dec_fixed32, + &pb_dec_fixed64, + + &pb_dec_bytes, + &pb_dec_string, + &pb_dec_submessage, + NULL /* extensions */ +}; + +/******************************* + * pb_istream_t implementation * + *******************************/ + +static bool checkreturn buf_read(pb_istream_t *stream, uint8_t *buf, size_t count) +{ + uint8_t *source = (uint8_t*)stream->state; + stream->state = source + count; + + if (buf != NULL) + { + while (count--) + *buf++ = *source++; + } + + return true; +} + +bool checkreturn pb_read(pb_istream_t *stream, uint8_t *buf, size_t count) +{ +#ifndef PB_BUFFER_ONLY + if (buf == NULL && stream->callback != buf_read) + { + /* Skip input bytes */ + uint8_t tmp[16]; + while (count > 16) + { + if (!pb_read(stream, tmp, 16)) + return false; + + count -= 16; + } + + return pb_read(stream, tmp, count); + } +#endif + + if (stream->bytes_left < count) + PB_RETURN_ERROR(stream, "end-of-stream"); + +#ifndef PB_BUFFER_ONLY + if (!stream->callback(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +#else + if (!buf_read(stream, buf, count)) + return false; +#endif + + stream->bytes_left -= count; + return true; +} + +/* Read a single byte from input stream. buf may not be NULL. + * This is an optimization for the varint decoding. */ +static bool checkreturn pb_readbyte(pb_istream_t *stream, uint8_t *buf) +{ + if (stream->bytes_left == 0) + PB_RETURN_ERROR(stream, "end-of-stream"); + +#ifndef PB_BUFFER_ONLY + if (!stream->callback(stream, buf, 1)) + PB_RETURN_ERROR(stream, "io error"); +#else + *buf = *(uint8_t*)stream->state; + stream->state = (uint8_t*)stream->state + 1; +#endif + + stream->bytes_left--; + + return true; +} + +pb_istream_t pb_istream_from_buffer(uint8_t *buf, size_t bufsize) +{ + pb_istream_t stream; +#ifdef PB_BUFFER_ONLY + stream.callback = NULL; +#else + stream.callback = &buf_read; +#endif + stream.state = buf; + stream.bytes_left = bufsize; +#ifndef PB_NO_ERRMSG + stream.errmsg = NULL; +#endif + return stream; +} + +/******************** + * Helper functions * + ********************/ + +static bool checkreturn pb_decode_varint32(pb_istream_t *stream, uint32_t *dest) +{ + uint8_t byte; + uint32_t result; + + if (!pb_readbyte(stream, &byte)) + return false; + + if ((byte & 0x80) == 0) + { + /* Quick case, 1 byte value */ + result = byte; + } + else + { + /* Multibyte case */ + uint8_t bitpos = 7; + result = byte & 0x7F; + + do + { + if (bitpos >= 32) + PB_RETURN_ERROR(stream, "varint overflow"); + + if (!pb_readbyte(stream, &byte)) + return false; + + result |= (uint32_t)(byte & 0x7F) << bitpos; + bitpos = (uint8_t)(bitpos + 7); + } while (byte & 0x80); + } + + *dest = result; + return true; +} + +bool checkreturn pb_decode_varint(pb_istream_t *stream, uint64_t *dest) +{ + uint8_t byte; + uint8_t bitpos = 0; + uint64_t result = 0; + + do + { + if (bitpos >= 64) + PB_RETURN_ERROR(stream, "varint overflow"); + + if (!pb_readbyte(stream, &byte)) + return false; + + result |= (uint64_t)(byte & 0x7F) << bitpos; + bitpos = (uint8_t)(bitpos + 7); + } while (byte & 0x80); + + *dest = result; + return true; +} + +bool checkreturn pb_skip_varint(pb_istream_t *stream) +{ + uint8_t byte; + do + { + if (!pb_read(stream, &byte, 1)) + return false; + } while (byte & 0x80); + return true; +} + +bool checkreturn pb_skip_string(pb_istream_t *stream) +{ + uint32_t length; + if (!pb_decode_varint32(stream, &length)) + return false; + + return pb_read(stream, NULL, length); +} + +bool checkreturn pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, uint32_t *tag, bool *eof) +{ + uint32_t temp; + *eof = false; + *wire_type = (pb_wire_type_t) 0; + *tag = 0; + + if (!pb_decode_varint32(stream, &temp)) + { + if (stream->bytes_left == 0) + *eof = true; + + return false; + } + + if (temp == 0) + { + *eof = true; /* Special feature: allow 0-terminated messages. */ + return false; + } + + *tag = temp >> 3; + *wire_type = (pb_wire_type_t)(temp & 7); + return true; +} + +bool checkreturn pb_skip_field(pb_istream_t *stream, pb_wire_type_t wire_type) +{ + switch (wire_type) + { + case PB_WT_VARINT: return pb_skip_varint(stream); + case PB_WT_64BIT: return pb_read(stream, NULL, 8); + case PB_WT_STRING: return pb_skip_string(stream); + case PB_WT_32BIT: return pb_read(stream, NULL, 4); + default: PB_RETURN_ERROR(stream, "invalid wire_type"); + } +} + +/* Read a raw value to buffer, for the purpose of passing it to callback as + * a substream. Size is maximum size on call, and actual size on return. + */ +static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire_type, uint8_t *buf, size_t *size) +{ + size_t max_size = *size; + switch (wire_type) + { + case PB_WT_VARINT: + *size = 0; + do + { + (*size)++; + if (*size > max_size) return false; + if (!pb_read(stream, buf, 1)) return false; + } while (*buf++ & 0x80); + return true; + + case PB_WT_64BIT: + *size = 8; + return pb_read(stream, buf, 8); + + case PB_WT_32BIT: + *size = 4; + return pb_read(stream, buf, 4); + + default: PB_RETURN_ERROR(stream, "invalid wire_type"); + } +} + +/* Decode string length from stream and return a substream with limited length. + * Remember to close the substream using pb_close_string_substream(). + */ +bool checkreturn pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream) +{ + uint32_t size; + if (!pb_decode_varint32(stream, &size)) + return false; + + *substream = *stream; + if (substream->bytes_left < size) + PB_RETURN_ERROR(stream, "parent stream too short"); + + substream->bytes_left = size; + stream->bytes_left -= size; + return true; +} + +void pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream) +{ + stream->state = substream->state; + +#ifndef PB_NO_ERRMSG + stream->errmsg = substream->errmsg; +#endif +} + +static void pb_field_init(pb_field_iterator_t *iter, const pb_field_t *fields, void *dest_struct) +{ + iter->start = iter->pos = fields; + iter->field_index = 0; + iter->required_field_index = 0; + iter->pData = (char*)dest_struct + iter->pos->data_offset; + iter->pSize = (char*)iter->pData + iter->pos->size_offset; + iter->dest_struct = dest_struct; +} + +static bool pb_field_next(pb_field_iterator_t *iter) +{ + bool notwrapped = true; + size_t prev_size = iter->pos->data_size; + + if (PB_ATYPE(iter->pos->type) == PB_ATYPE_STATIC && + PB_HTYPE(iter->pos->type) == PB_HTYPE_REPEATED) + { + prev_size *= iter->pos->array_size; + } + else if (PB_ATYPE(iter->pos->type) == PB_ATYPE_POINTER) + { + prev_size = sizeof(void*); + } + + if (iter->pos->tag == 0) + return false; /* Only happens with empty message types */ + + if (PB_HTYPE(iter->pos->type) == PB_HTYPE_REQUIRED) + iter->required_field_index++; + + iter->pos++; + iter->field_index++; + if (iter->pos->tag == 0) + { + iter->pos = iter->start; + iter->field_index = 0; + iter->required_field_index = 0; + iter->pData = iter->dest_struct; + prev_size = 0; + notwrapped = false; + } + + iter->pData = (char*)iter->pData + prev_size + iter->pos->data_offset; + iter->pSize = (char*)iter->pData + iter->pos->size_offset; + return notwrapped; +} + +static bool checkreturn pb_field_find(pb_field_iterator_t *iter, uint32_t tag) +{ + unsigned start = iter->field_index; + + do { + if (iter->pos->tag == tag && + PB_LTYPE(iter->pos->type) != PB_LTYPE_EXTENSION) + { + return true; + } + (void)pb_field_next(iter); + } while (iter->field_index != start); + + return false; +} + +/************************* + * Decode a single field * + *************************/ + +static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) +{ + pb_type_t type; + pb_decoder_t func; + + type = iter->pos->type; + func = PB_DECODERS[PB_LTYPE(type)]; + + switch (PB_HTYPE(type)) + { + case PB_HTYPE_REQUIRED: + return func(stream, iter->pos, iter->pData); + + case PB_HTYPE_OPTIONAL: + *(bool*)iter->pSize = true; + return func(stream, iter->pos, iter->pData); + + case PB_HTYPE_REPEATED: + if (wire_type == PB_WT_STRING + && PB_LTYPE(type) <= PB_LTYPE_LAST_PACKABLE) + { + /* Packed array */ + bool status = true; + size_t *size = (size_t*)iter->pSize; + pb_istream_t substream; + if (!pb_make_string_substream(stream, &substream)) + return false; + + while (substream.bytes_left > 0 && *size < iter->pos->array_size) + { + void *pItem = (uint8_t*)iter->pData + iter->pos->data_size * (*size); + if (!func(&substream, iter->pos, pItem)) + { + status = false; + break; + } + (*size)++; + } + pb_close_string_substream(stream, &substream); + + if (substream.bytes_left != 0) + PB_RETURN_ERROR(stream, "array overflow"); + + return status; + } + else + { + /* Repeated field */ + size_t *size = (size_t*)iter->pSize; + void *pItem = (uint8_t*)iter->pData + iter->pos->data_size * (*size); + if (*size >= iter->pos->array_size) + PB_RETURN_ERROR(stream, "array overflow"); + + (*size)++; + return func(stream, iter->pos, pItem); + } + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +#ifdef PB_ENABLE_MALLOC +/* Allocate storage for the field and store the pointer at iter->pData. + * array_size is the number of entries to reserve in an array. + */ +static bool checkreturn allocate_field(pb_istream_t *stream, void *pData, size_t data_size, size_t array_size) +{ + void *ptr = *(void**)pData; + + /* Check for multiplication overflows. */ + size_t size = 0; + if (data_size > 0 && array_size > 0) + { + /* Avoid the costly division if the sizes are small enough. + * Multiplication is safe as long as only half of bits are set + * in either multiplicand. + */ + const size_t check_limit = (size_t)1 << (sizeof(size_t) * 4); + if (data_size >= check_limit || array_size >= check_limit) + { + if (SIZE_MAX / array_size < data_size) + { + PB_RETURN_ERROR(stream, "size too large"); + } + } + + size = array_size * data_size; + } + + /* Allocate new or expand previous allocation */ + /* Note: on failure the old pointer will remain in the structure, + * the message must be freed by caller also on error return. */ + ptr = pb_realloc(ptr, size); + if (ptr == NULL) + PB_RETURN_ERROR(stream, "realloc failed"); + + *(void**)pData = ptr; + return true; +} + +/* Clear a newly allocated item in case it contains a pointer, or is a submessage. */ +static void initialize_pointer_field(void *pItem, pb_field_iterator_t *iter) +{ + if (PB_LTYPE(iter->pos->type) == PB_LTYPE_STRING || + PB_LTYPE(iter->pos->type) == PB_LTYPE_BYTES) + { + *(void**)pItem = NULL; + } + else if (PB_LTYPE(iter->pos->type) == PB_LTYPE_SUBMESSAGE) + { + pb_message_set_to_defaults((const pb_field_t *) iter->pos->ptr, pItem); + } +} +#endif + +static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) +{ +#ifndef PB_ENABLE_MALLOC + UNUSED(wire_type); + UNUSED(iter); + PB_RETURN_ERROR(stream, "no malloc support"); +#else + pb_type_t type; + pb_decoder_t func; + + type = iter->pos->type; + func = PB_DECODERS[PB_LTYPE(type)]; + + switch (PB_HTYPE(type)) + { + case PB_HTYPE_REQUIRED: + case PB_HTYPE_OPTIONAL: + if (PB_LTYPE(type) == PB_LTYPE_STRING || + PB_LTYPE(type) == PB_LTYPE_BYTES) + { + return func(stream, iter->pos, iter->pData); + } + else + { + if (!allocate_field(stream, iter->pData, iter->pos->data_size, 1)) + return false; + + initialize_pointer_field(*(void**)iter->pData, iter); + return func(stream, iter->pos, *(void**)iter->pData); + } + + case PB_HTYPE_REPEATED: + if (wire_type == PB_WT_STRING + && PB_LTYPE(type) <= PB_LTYPE_LAST_PACKABLE) + { + /* Packed array, multiple items come in at once. */ + bool status = true; + size_t *size = (size_t*)iter->pSize; + size_t allocated_size = *size; + void *pItem; + pb_istream_t substream; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + while (substream.bytes_left) + { + if (*size + 1 > allocated_size) + { + /* Allocate more storage. This tries to guess the + * number of remaining entries. Round the division + * upwards. */ + allocated_size += (substream.bytes_left - 1) / iter->pos->data_size + 1; + + if (!allocate_field(&substream, iter->pData, iter->pos->data_size, allocated_size)) + { + status = false; + break; + } + } + + /* Decode the array entry */ + pItem = *(uint8_t**)iter->pData + iter->pos->data_size * (*size); + initialize_pointer_field(pItem, iter); + if (!func(&substream, iter->pos, pItem)) + { + status = false; + break; + } + (*size)++; + } + pb_close_string_substream(stream, &substream); + + return status; + } + else + { + /* Normal repeated field, i.e. only one item at a time. */ + size_t *size = (size_t*)iter->pSize; + void *pItem; + + (*size)++; + if (!allocate_field(stream, iter->pData, iter->pos->data_size, *size)) + return false; + + pItem = *(uint8_t**)iter->pData + iter->pos->data_size * (*size - 1); + initialize_pointer_field(pItem, iter); + return func(stream, iter->pos, pItem); + } + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +#endif +} + +static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) +{ + pb_callback_t *pCallback = (pb_callback_t*)iter->pData; + +#ifdef PB_OLD_CALLBACK_STYLE + void *arg = pCallback->arg; +#else + void **arg = &(pCallback->arg); +#endif + + if (pCallback->funcs.decode == NULL) + return pb_skip_field(stream, wire_type); + + if (wire_type == PB_WT_STRING) + { + pb_istream_t substream; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + do + { + if (!pCallback->funcs.decode(&substream, iter->pos, arg)) + PB_RETURN_ERROR(stream, "callback failed"); + } while (substream.bytes_left); + + pb_close_string_substream(stream, &substream); + return true; + } + else + { + /* Copy the single scalar value to stack. + * This is required so that we can limit the stream length, + * which in turn allows to use same callback for packed and + * not-packed fields. */ + pb_istream_t substream; + uint8_t buffer[10]; + size_t size = sizeof(buffer); + + if (!read_raw_value(stream, wire_type, buffer, &size)) + return false; + substream = pb_istream_from_buffer(buffer, size); + + return pCallback->funcs.decode(&substream, iter->pos, arg); + } +} + +static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) +{ + switch (PB_ATYPE(iter->pos->type)) + { + case PB_ATYPE_STATIC: + return decode_static_field(stream, wire_type, iter); + + case PB_ATYPE_POINTER: + return decode_pointer_field(stream, wire_type, iter); + + case PB_ATYPE_CALLBACK: + return decode_callback_field(stream, wire_type, iter); + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +/* Default handler for extension fields. Expects a pb_field_t structure + * in extension->type->arg. */ +static bool checkreturn default_extension_decoder(pb_istream_t *stream, + pb_extension_t *extension, uint32_t tag, pb_wire_type_t wire_type) +{ + const pb_field_t *field = (const pb_field_t*)extension->type->arg; + pb_field_iterator_t iter; + + if (field->tag != tag) + return true; + + iter.start = field; + iter.pos = field; + iter.field_index = 0; + iter.required_field_index = 0; + iter.dest_struct = extension->dest; + iter.pData = extension->dest; + iter.pSize = &extension->found; + + return decode_field(stream, wire_type, &iter); +} + +/* Try to decode an unknown field as an extension field. Tries each extension + * decoder in turn, until one of them handles the field or loop ends. */ +static bool checkreturn decode_extension(pb_istream_t *stream, + uint32_t tag, pb_wire_type_t wire_type, pb_field_iterator_t *iter) +{ + pb_extension_t *extension = *(pb_extension_t* const *)iter->pData; + size_t pos = stream->bytes_left; + + while (extension != NULL && pos == stream->bytes_left) + { + bool status; + if (extension->type->decode) + status = extension->type->decode(stream, extension, tag, wire_type); + else + status = default_extension_decoder(stream, extension, tag, wire_type); + + if (!status) + return false; + + extension = extension->next; + } + + return true; +} + +/* Step through the iterator until an extension field is found or until all + * entries have been checked. There can be only one extension field per + * message. Returns false if no extension field is found. */ +static bool checkreturn find_extension_field(pb_field_iterator_t *iter) +{ + unsigned start = iter->field_index; + + do { + if (PB_LTYPE(iter->pos->type) == PB_LTYPE_EXTENSION) + return true; + (void)pb_field_next(iter); + } while (iter->field_index != start); + + return false; +} + +/* Initialize message fields to default values, recursively */ +static void pb_message_set_to_defaults(const pb_field_t fields[], void *dest_struct) +{ + pb_field_iterator_t iter; + pb_field_init(&iter, fields, dest_struct); + + do + { + pb_type_t type; + type = iter.pos->type; + + /* Avoid crash on empty message types (zero fields) */ + if (iter.pos->tag == 0) + continue; + + if (PB_ATYPE(type) == PB_ATYPE_STATIC) + { + if (PB_HTYPE(type) == PB_HTYPE_OPTIONAL) + { + /* Set has_field to false. Still initialize the optional field + * itself also. */ + *(bool*)iter.pSize = false; + } + else if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + /* Set array count to 0, no need to initialize contents. */ + *(size_t*)iter.pSize = 0; + continue; + } + + if (PB_LTYPE(iter.pos->type) == PB_LTYPE_SUBMESSAGE) + { + /* Initialize submessage to defaults */ + pb_message_set_to_defaults((const pb_field_t *) iter.pos->ptr, iter.pData); + } + else if (iter.pos->ptr != NULL) + { + /* Initialize to default value */ + memcpy(iter.pData, iter.pos->ptr, iter.pos->data_size); + } + else + { + /* Initialize to zeros */ + memset(iter.pData, 0, iter.pos->data_size); + } + } + else if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + /* Initialize the pointer to NULL. */ + *(void**)iter.pData = NULL; + + /* Initialize array count to 0. */ + if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + *(size_t*)iter.pSize = 0; + } + } + else if (PB_ATYPE(type) == PB_ATYPE_CALLBACK) + { + /* Don't overwrite callback */ + } + } while (pb_field_next(&iter)); +} + +/********************* + * Decode all fields * + *********************/ + +bool checkreturn pb_decode_noinit(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct) +{ + uint8_t fields_seen[(PB_MAX_REQUIRED_FIELDS + 7) / 8] = {0, 0, 0, 0, 0, 0, 0, 0}; + uint32_t extension_range_start = 0; + pb_field_iterator_t iter; + + pb_field_init(&iter, fields, dest_struct); + + while (stream->bytes_left) + { + uint32_t tag; + pb_wire_type_t wire_type; + bool eof; + + if (!pb_decode_tag(stream, &wire_type, &tag, &eof)) + { + if (eof) + break; + else + return false; + } + + if (!pb_field_find(&iter, tag)) + { + /* No match found, check if it matches an extension. */ + if (tag >= extension_range_start) + { + if (!find_extension_field(&iter)) + extension_range_start = (uint32_t)-1; + else + extension_range_start = iter.pos->tag; + + if (tag >= extension_range_start) + { + size_t pos = stream->bytes_left; + + if (!decode_extension(stream, tag, wire_type, &iter)) + return false; + + if (pos != stream->bytes_left) + { + /* The field was handled */ + continue; + } + } + } + + /* No match found, skip data */ + if (!pb_skip_field(stream, wire_type)) + return false; + continue; + } + + if (PB_HTYPE(iter.pos->type) == PB_HTYPE_REQUIRED + && iter.required_field_index < PB_MAX_REQUIRED_FIELDS) + { + fields_seen[iter.required_field_index >> 3] |= (uint8_t)(1 << (iter.required_field_index & 7)); + } + + if (!decode_field(stream, wire_type, &iter)) + return false; + } + + /* Check that all required fields were present. */ + { + /* First figure out the number of required fields by + * seeking to the end of the field array. Usually we + * are already close to end after decoding. + */ + unsigned req_field_count; + pb_type_t last_type; + unsigned i; + do { + req_field_count = iter.required_field_index; + last_type = iter.pos->type; + } while (pb_field_next(&iter)); + + /* Fixup if last field was also required. */ + if (PB_HTYPE(last_type) == PB_HTYPE_REQUIRED && iter.pos->tag != 0) + req_field_count++; + + /* Check the whole bytes */ + for (i = 0; i < (req_field_count >> 3); i++) + { + if (fields_seen[i] != 0xFF) + PB_RETURN_ERROR(stream, "missing required field"); + } + + /* Check the remaining bits */ + if (fields_seen[req_field_count >> 3] != (0xFF >> (8 - (req_field_count & 7)))) + PB_RETURN_ERROR(stream, "missing required field"); + } + + return true; +} + +bool checkreturn pb_decode(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct) +{ + bool status; + pb_message_set_to_defaults(fields, dest_struct); + status = pb_decode_noinit(stream, fields, dest_struct); + +#ifdef PB_ENABLE_MALLOC + if (!status) + pb_release(fields, dest_struct); +#endif + + return status; +} + +bool pb_decode_delimited(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct) +{ + pb_istream_t substream; + bool status; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + status = pb_decode(&substream, fields, dest_struct); + pb_close_string_substream(stream, &substream); + return status; +} + +#ifdef PB_ENABLE_MALLOC +void pb_release(const pb_field_t fields[], void *dest_struct) +{ + pb_field_iterator_t iter; + pb_field_init(&iter, fields, dest_struct); + + do + { + pb_type_t type; + type = iter.pos->type; + + /* Avoid crash on empty message types (zero fields) */ + if (iter.pos->tag == 0) + continue; + + if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + if (PB_HTYPE(type) == PB_HTYPE_REPEATED && + (PB_LTYPE(type) == PB_LTYPE_STRING || + PB_LTYPE(type) == PB_LTYPE_BYTES)) + { + /* Release entries in repeated string or bytes array */ + void **pItem = *(void***)iter.pData; + size_t count = *(size_t*)iter.pSize; + while (count--) + { + pb_free(*pItem); + *pItem++ = NULL; + } + } + else if (PB_LTYPE(type) == PB_LTYPE_SUBMESSAGE) + { + /* Release fields in submessages */ + void *pItem = *(void**)iter.pData; + size_t count = (pItem ? 1 : 0); + + if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + count = *(size_t*)iter.pSize; + } + + while (count--) + { + pb_release((const pb_field_t*)iter.pos->ptr, pItem); + pItem = (uint8_t*)pItem + iter.pos->data_size; + } + } + + /* Release main item */ + pb_free(*(void**)iter.pData); + *(void**)iter.pData = NULL; + } + } while (pb_field_next(&iter)); +} +#endif + +/* Field decoders */ + +bool pb_decode_svarint(pb_istream_t *stream, int64_t *dest) +{ + uint64_t value; + if (!pb_decode_varint(stream, &value)) + return false; + + if (value & 1) + *dest = (int64_t)(~(value >> 1)); + else + *dest = (int64_t)(value >> 1); + + return true; +} + +bool pb_decode_fixed32(pb_istream_t *stream, void *dest) +{ + #ifdef __BIG_ENDIAN__ + uint8_t *bytes = (uint8_t*)dest; + uint8_t lebytes[4]; + + if (!pb_read(stream, lebytes, 4)) + return false; + + bytes[0] = lebytes[3]; + bytes[1] = lebytes[2]; + bytes[2] = lebytes[1]; + bytes[3] = lebytes[0]; + return true; + #else + return pb_read(stream, (uint8_t*)dest, 4); + #endif +} + +bool pb_decode_fixed64(pb_istream_t *stream, void *dest) +{ + #ifdef __BIG_ENDIAN__ + uint8_t *bytes = (uint8_t*)dest; + uint8_t lebytes[8]; + + if (!pb_read(stream, lebytes, 8)) + return false; + + bytes[0] = lebytes[7]; + bytes[1] = lebytes[6]; + bytes[2] = lebytes[5]; + bytes[3] = lebytes[4]; + bytes[4] = lebytes[3]; + bytes[5] = lebytes[2]; + bytes[6] = lebytes[1]; + bytes[7] = lebytes[0]; + return true; + #else + return pb_read(stream, (uint8_t*)dest, 8); + #endif +} + +static bool checkreturn pb_dec_varint(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + uint64_t value; + if (!pb_decode_varint(stream, &value)) + return false; + + switch (field->data_size) + { + case 1: *(int8_t*)dest = (int8_t)value; break; + case 2: *(int16_t*)dest = (int16_t)value; break; + case 4: *(int32_t*)dest = (int32_t)value; break; + case 8: *(int64_t*)dest = (int64_t)value; break; + default: PB_RETURN_ERROR(stream, "invalid data_size"); + } + + return true; +} + +static bool checkreturn pb_dec_uvarint(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + uint64_t value; + if (!pb_decode_varint(stream, &value)) + return false; + + switch (field->data_size) + { + case 4: *(uint32_t*)dest = (uint32_t)value; break; + case 8: *(uint64_t*)dest = value; break; + default: PB_RETURN_ERROR(stream, "invalid data_size"); + } + + return true; +} + +static bool checkreturn pb_dec_svarint(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + int64_t value; + if (!pb_decode_svarint(stream, &value)) + return false; + + switch (field->data_size) + { + case 4: *(int32_t*)dest = (int32_t)value; break; + case 8: *(int64_t*)dest = value; break; + default: PB_RETURN_ERROR(stream, "invalid data_size"); + } + + return true; +} + +static bool checkreturn pb_dec_fixed32(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + UNUSED(field); + return pb_decode_fixed32(stream, dest); +} + +static bool checkreturn pb_dec_fixed64(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + UNUSED(field); + return pb_decode_fixed64(stream, dest); +} + +static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + uint32_t size; + pb_bytes_array_t *bdest; + + if (!pb_decode_varint32(stream, &size)) + return false; + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { +#ifndef PB_ENABLE_MALLOC + PB_RETURN_ERROR(stream, "no malloc support"); +#else + if (!allocate_field(stream, dest, PB_BYTES_ARRAY_T_ALLOCSIZE(size), 1)) + return false; + bdest = *(pb_bytes_array_t**)dest; +#endif + } + else + { + if (PB_BYTES_ARRAY_T_ALLOCSIZE(size) > field->data_size) + PB_RETURN_ERROR(stream, "bytes overflow"); + bdest = (pb_bytes_array_t*)dest; + } + + bdest->size = size; + return pb_read(stream, bdest->bytes, size); +} + +static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + uint32_t size; + size_t alloc_size; + bool status; + if (!pb_decode_varint32(stream, &size)) + return false; + + /* Space for null terminator */ + alloc_size = size + 1; + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { +#ifndef PB_ENABLE_MALLOC + PB_RETURN_ERROR(stream, "no malloc support"); +#else + if (!allocate_field(stream, dest, alloc_size, 1)) + return false; + dest = *(void**)dest; +#endif + } + else + { + if (alloc_size > field->data_size) + PB_RETURN_ERROR(stream, "string overflow"); + } + + status = pb_read(stream, (uint8_t*)dest, size); + *((uint8_t*)dest + size) = 0; + return status; +} + +static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_t *field, void *dest) +{ + bool status; + pb_istream_t substream; + const pb_field_t* submsg_fields = (const pb_field_t*)field->ptr; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + if (field->ptr == NULL) + PB_RETURN_ERROR(stream, "invalid field descriptor"); + + /* New array entries need to be initialized, while required and optional + * submessages have already been initialized in the top-level pb_decode. */ + if (PB_HTYPE(field->type) == PB_HTYPE_REPEATED) + status = pb_decode(&substream, submsg_fields, dest); + else + status = pb_decode_noinit(&substream, submsg_fields, dest); + + pb_close_string_substream(stream, &substream); + return status; +} diff --git a/fri_client/third_party/nanopb/src/pb_encode.c b/fri_client/third_party/nanopb/src/pb_encode.c new file mode 100644 index 00000000..7fcc5745 --- /dev/null +++ b/fri_client/third_party/nanopb/src/pb_encode.c @@ -0,0 +1,671 @@ +/* pb_encode.c -- encode a protobuf using minimal resources + * + * 2011 Petteri Aimonen + */ + +#include +#include + +/* Use the GCC warn_unused_result attribute to check that all return values + * are propagated correctly. On other compilers and gcc before 3.4.0 just + * ignore the annotation. + */ +#if !defined(__GNUC__) || ( __GNUC__ < 3) || (__GNUC__ == 3 && __GNUC_MINOR__ < 4) + #define checkreturn +#else + #define checkreturn __attribute__((warn_unused_result)) +#endif + +/************************************** + * Declarations internal to this file * + **************************************/ +typedef bool (*pb_encoder_t)(pb_ostream_t *stream, const pb_field_t *field, const void *src) checkreturn; + +static bool checkreturn buf_write(pb_ostream_t *stream, const uint8_t *buf, size_t count); +static bool checkreturn encode_array(pb_ostream_t *stream, const pb_field_t *field, const void *pData, size_t count, pb_encoder_t func); +static bool checkreturn encode_field(pb_ostream_t *stream, const pb_field_t *field, const void *pData); +static bool checkreturn default_extension_encoder(pb_ostream_t *stream, const pb_extension_t *extension); +static bool checkreturn encode_extension_field(pb_ostream_t *stream, const pb_field_t *field, const void *pData); +static bool checkreturn pb_enc_varint(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_uvarint(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_svarint(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_fixed32(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_fixed64(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_t *field, const void *src); +static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_t *field, const void *src); + +/* --- Function pointers to field encoders --- + * Order in the array must match pb_action_t LTYPE numbering. + */ +static const pb_encoder_t PB_ENCODERS[PB_LTYPES_COUNT] = { + &pb_enc_varint, + &pb_enc_uvarint, + &pb_enc_svarint, + &pb_enc_fixed32, + &pb_enc_fixed64, + + &pb_enc_bytes, + &pb_enc_string, + &pb_enc_submessage, + NULL /* extensions */ +}; + +/******************************* + * pb_ostream_t implementation * + *******************************/ + +static bool checkreturn buf_write(pb_ostream_t *stream, const uint8_t *buf, size_t count) +{ + uint8_t *dest = (uint8_t*)stream->state; + stream->state = dest + count; + + while (count--) + *dest++ = *buf++; + + return true; +} + +pb_ostream_t pb_ostream_from_buffer(uint8_t *buf, size_t bufsize) +{ + pb_ostream_t stream; +#ifdef PB_BUFFER_ONLY + stream.callback = (void*)1; /* Just a marker value */ +#else + stream.callback = &buf_write; +#endif + stream.state = buf; + stream.max_size = bufsize; + stream.bytes_written = 0; +#ifndef PB_NO_ERRMSG + stream.errmsg = NULL; +#endif + return stream; +} + +bool checkreturn pb_write(pb_ostream_t *stream, const uint8_t *buf, size_t count) +{ + if (stream->callback != NULL) + { + if (stream->bytes_written + count > stream->max_size) + PB_RETURN_ERROR(stream, "stream full"); + +#ifdef PB_BUFFER_ONLY + if (!buf_write(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +#else + if (!stream->callback(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +#endif + } + + stream->bytes_written += count; + return true; +} + +/************************* + * Encode a single field * + *************************/ + +/* Encode a static array. Handles the size calculations and possible packing. */ +static bool checkreturn encode_array(pb_ostream_t *stream, const pb_field_t *field, + const void *pData, size_t count, pb_encoder_t func) +{ + size_t i; + const void *p; + size_t size; + + if (count == 0) + return true; + + if (PB_ATYPE(field->type) != PB_ATYPE_POINTER && count > field->array_size) + PB_RETURN_ERROR(stream, "array max size exceeded"); + + /* We always pack arrays if the datatype allows it. */ + if (PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) + { + if (!pb_encode_tag(stream, PB_WT_STRING, field->tag)) + return false; + + /* Determine the total size of packed array. */ + if (PB_LTYPE(field->type) == PB_LTYPE_FIXED32) + { + size = 4 * count; + } + else if (PB_LTYPE(field->type) == PB_LTYPE_FIXED64) + { + size = 8 * count; + } + else + { + pb_ostream_t sizestream = PB_OSTREAM_SIZING; + p = pData; + for (i = 0; i < count; i++) + { + if (!func(&sizestream, field, p)) + return false; + p = (const char*)p + field->data_size; + } + size = sizestream.bytes_written; + } + + if (!pb_encode_varint(stream, (uint64_t)size)) + return false; + + if (stream->callback == NULL) + return pb_write(stream, NULL, size); /* Just sizing.. */ + + /* Write the data */ + p = pData; + for (i = 0; i < count; i++) + { + if (!func(stream, field, p)) + return false; + p = (const char*)p + field->data_size; + } + } + else + { + p = pData; + for (i = 0; i < count; i++) + { + if (!pb_encode_tag_for_field(stream, field)) + return false; + + /* Normally the data is stored directly in the array entries, but + * for pointer-type string and bytes fields, the array entries are + * actually pointers themselves also. So we have to dereference once + * more to get to the actual data. */ + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER && + (PB_LTYPE(field->type) == PB_LTYPE_STRING || + PB_LTYPE(field->type) == PB_LTYPE_BYTES)) + { + if (!func(stream, field, *(const void* const*)p)) + return false; + } + else + { + if (!func(stream, field, p)) + return false; + } + p = (const char*)p + field->data_size; + } + } + + return true; +} + +/* Encode a field with static or pointer allocation, i.e. one whose data + * is available to the encoder directly. */ +static bool checkreturn encode_basic_field(pb_ostream_t *stream, + const pb_field_t *field, const void *pData) +{ + pb_encoder_t func; + const void *pSize; + bool implicit_has = true; + + func = PB_ENCODERS[PB_LTYPE(field->type)]; + + if (field->size_offset) + pSize = (const char*)pData + field->size_offset; + else + pSize = &implicit_has; + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { + /* pData is a pointer to the field, which contains pointer to + * the data. If the 2nd pointer is NULL, it is interpreted as if + * the has_field was false. + */ + + pData = *(const void* const*)pData; + implicit_has = (pData != NULL); + } + + switch (PB_HTYPE(field->type)) + { + case PB_HTYPE_REQUIRED: + if (!pData) + PB_RETURN_ERROR(stream, "missing required field"); + if (!pb_encode_tag_for_field(stream, field)) + return false; + if (!func(stream, field, pData)) + return false; + break; + + case PB_HTYPE_OPTIONAL: + /* + * KUKA adjustment for VxWorks + */ + + if (*(const char*)pSize) + { + if (!pb_encode_tag_for_field(stream, field)) + return false; + + if (!func(stream, field, pData)) + return false; + } + break; + + case PB_HTYPE_REPEATED: + if (!encode_array(stream, field, pData, *(const size_t*)pSize, func)) + return false; + break; + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } + + return true; +} + +/* Encode a field with callback semantics. This means that a user function is + * called to provide and encode the actual data. */ +static bool checkreturn encode_callback_field(pb_ostream_t *stream, + const pb_field_t *field, const void *pData) +{ + const pb_callback_t *callback = (const pb_callback_t*)pData; + +#ifdef PB_OLD_CALLBACK_STYLE + const void *arg = callback->arg; +#else + void * const *arg = &(callback->arg); +#endif + + if (callback->funcs.encode != NULL) + { + if (!callback->funcs.encode(stream, field, arg)) + PB_RETURN_ERROR(stream, "callback error"); + } + return true; +} + +/* Encode a single field of any callback or static type. */ +static bool checkreturn encode_field(pb_ostream_t *stream, + const pb_field_t *field, const void *pData) +{ + switch (PB_ATYPE(field->type)) + { + case PB_ATYPE_STATIC: + case PB_ATYPE_POINTER: + return encode_basic_field(stream, field, pData); + + case PB_ATYPE_CALLBACK: + return encode_callback_field(stream, field, pData); + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +/* Default handler for extension fields. Expects to have a pb_field_t + * pointer in the extension->type->arg field. */ +static bool checkreturn default_extension_encoder(pb_ostream_t *stream, + const pb_extension_t *extension) +{ + const pb_field_t *field = (const pb_field_t*)extension->type->arg; + return encode_field(stream, field, extension->dest); +} + +/* Walk through all the registered extensions and give them a chance + * to encode themselves. */ +static bool checkreturn encode_extension_field(pb_ostream_t *stream, + const pb_field_t *field, const void *pData) +{ + const pb_extension_t *extension = *(const pb_extension_t* const *)pData; + UNUSED(field); + + while (extension) + { + bool status; + if (extension->type->encode) + status = extension->type->encode(stream, extension); + else + status = default_extension_encoder(stream, extension); + + if (!status) + return false; + + extension = extension->next; + } + + return true; +} + +/********************* + * Encode all fields * + *********************/ + +bool checkreturn pb_encode(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct) +{ + const pb_field_t *field = fields; + const void *pData = src_struct; + size_t prev_size = 0; + + while (field->tag != 0) + { + pData = (const char*)pData + prev_size + field->data_offset; + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + prev_size = sizeof(const void*); + else + prev_size = field->data_size; + + /* Special case for static arrays */ + if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && + PB_HTYPE(field->type) == PB_HTYPE_REPEATED) + { + prev_size *= field->array_size; + } + + if (PB_LTYPE(field->type) == PB_LTYPE_EXTENSION) + { + /* Special case for the extension field placeholder */ + if (!encode_extension_field(stream, field, pData)) + return false; + } + else + { + /* Regular field */ + if (!encode_field(stream, field, pData)) + return false; + } + + field++; + } + + return true; +} + +bool pb_encode_delimited(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct) +{ + return pb_encode_submessage(stream, fields, src_struct); +} + +bool pb_get_encoded_size(size_t *size, const pb_field_t fields[], const void *src_struct) +{ + pb_ostream_t stream = PB_OSTREAM_SIZING; + + if (!pb_encode(&stream, fields, src_struct)) + return false; + + *size = stream.bytes_written; + return true; +} + +/******************** + * Helper functions * + ********************/ +bool checkreturn pb_encode_varint(pb_ostream_t *stream, uint64_t value) +{ + uint8_t buffer[10]; + size_t i = 0; + + if (value == 0) + return pb_write(stream, (uint8_t*)&value, 1); + + while (value) + { + buffer[i] = (uint8_t)((value & 0x7F) | 0x80); + value >>= 7; + i++; + } + buffer[i-1] &= 0x7F; /* Unset top bit on last byte */ + + return pb_write(stream, buffer, i); +} + +bool checkreturn pb_encode_svarint(pb_ostream_t *stream, int64_t value) +{ + uint64_t zigzagged; + if (value < 0) + zigzagged = ~((uint64_t)value << 1); + else + zigzagged = (uint64_t)value << 1; + + return pb_encode_varint(stream, zigzagged); +} + +bool checkreturn pb_encode_fixed32(pb_ostream_t *stream, const void *value) +{ + #ifdef __BIG_ENDIAN__ + const uint8_t *bytes = value; + uint8_t lebytes[4]; + lebytes[0] = bytes[3]; + lebytes[1] = bytes[2]; + lebytes[2] = bytes[1]; + lebytes[3] = bytes[0]; + return pb_write(stream, lebytes, 4); + #else + return pb_write(stream, (const uint8_t*)value, 4); + #endif +} + +bool checkreturn pb_encode_fixed64(pb_ostream_t *stream, const void *value) +{ + #ifdef __BIG_ENDIAN__ + const uint8_t *bytes = value; + uint8_t lebytes[8]; + lebytes[0] = bytes[7]; + lebytes[1] = bytes[6]; + lebytes[2] = bytes[5]; + lebytes[3] = bytes[4]; + lebytes[4] = bytes[3]; + lebytes[5] = bytes[2]; + lebytes[6] = bytes[1]; + lebytes[7] = bytes[0]; + return pb_write(stream, lebytes, 8); + #else + return pb_write(stream, (const uint8_t*)value, 8); + #endif +} + +bool checkreturn pb_encode_tag(pb_ostream_t *stream, pb_wire_type_t wiretype, uint32_t field_number) +{ + uint64_t tag = ((uint64_t)field_number << 3) | wiretype; + return pb_encode_varint(stream, tag); +} + +bool checkreturn pb_encode_tag_for_field(pb_ostream_t *stream, const pb_field_t *field) +{ + pb_wire_type_t wiretype; + switch (PB_LTYPE(field->type)) + { + case PB_LTYPE_VARINT: + case PB_LTYPE_UVARINT: + case PB_LTYPE_SVARINT: + wiretype = PB_WT_VARINT; + break; + + case PB_LTYPE_FIXED32: + wiretype = PB_WT_32BIT; + break; + + case PB_LTYPE_FIXED64: + wiretype = PB_WT_64BIT; + break; + + case PB_LTYPE_BYTES: + case PB_LTYPE_STRING: + case PB_LTYPE_SUBMESSAGE: + wiretype = PB_WT_STRING; + break; + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } + + return pb_encode_tag(stream, wiretype, field->tag); +} + +bool checkreturn pb_encode_string(pb_ostream_t *stream, const uint8_t *buffer, size_t size) +{ + if (!pb_encode_varint(stream, (uint64_t)size)) + return false; + + return pb_write(stream, buffer, size); +} + +bool checkreturn pb_encode_submessage(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct) +{ + /* First calculate the message size using a non-writing substream. */ + pb_ostream_t substream = PB_OSTREAM_SIZING; + size_t size; + bool status; + + if (!pb_encode(&substream, fields, src_struct)) + { +#ifndef PB_NO_ERRMSG + stream->errmsg = substream.errmsg; +#endif + return false; + } + + size = substream.bytes_written; + + if (!pb_encode_varint(stream, (uint64_t)size)) + return false; + + if (stream->callback == NULL) + return pb_write(stream, NULL, size); /* Just sizing */ + + if (stream->bytes_written + size > stream->max_size) + PB_RETURN_ERROR(stream, "stream full"); + + /* Use a substream to verify that a callback doesn't write more than + * what it did the first time. */ + substream.callback = stream->callback; + substream.state = stream->state; + substream.max_size = size; + substream.bytes_written = 0; +#ifndef PB_NO_ERRMSG + substream.errmsg = NULL; +#endif + + status = pb_encode(&substream, fields, src_struct); + + stream->bytes_written += substream.bytes_written; + stream->state = substream.state; +#ifndef PB_NO_ERRMSG + stream->errmsg = substream.errmsg; +#endif + + if (substream.bytes_written != size) + PB_RETURN_ERROR(stream, "submsg size changed"); + + return status; +} + +/* Field encoders */ + +static bool checkreturn pb_enc_varint(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + int64_t value = 0; + + /* Cases 1 and 2 are for compilers that have smaller types for bool + * or enums. */ + switch (field->data_size) + { + case 1: value = *(const int8_t*)src; break; + case 2: value = *(const int16_t*)src; break; + case 4: value = *(const int32_t*)src; break; + case 8: value = *(const int64_t*)src; break; + default: PB_RETURN_ERROR(stream, "invalid data_size"); + } + + return pb_encode_varint(stream, (uint64_t)value); +} + +static bool checkreturn pb_enc_uvarint(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + uint64_t value = 0; + + switch (field->data_size) + { + case 4: value = *(const uint32_t*)src; break; + case 8: value = *(const uint64_t*)src; break; + default: PB_RETURN_ERROR(stream, "invalid data_size"); + } + + return pb_encode_varint(stream, value); +} + +static bool checkreturn pb_enc_svarint(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + int64_t value = 0; + + switch (field->data_size) + { + case 4: value = *(const int32_t*)src; break; + case 8: value = *(const int64_t*)src; break; + default: PB_RETURN_ERROR(stream, "invalid data_size"); + } + + return pb_encode_svarint(stream, value); +} + +static bool checkreturn pb_enc_fixed64(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + UNUSED(field); + return pb_encode_fixed64(stream, src); +} + +static bool checkreturn pb_enc_fixed32(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + UNUSED(field); + return pb_encode_fixed32(stream, src); +} + +static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + const pb_bytes_array_t *bytes = (const pb_bytes_array_t*)src; + + if (src == NULL) + { + /* Threat null pointer as an empty bytes field */ + return pb_encode_string(stream, NULL, 0); + } + + if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && + PB_BYTES_ARRAY_T_ALLOCSIZE(bytes->size) > field->data_size) + { + PB_RETURN_ERROR(stream, "bytes size exceeded"); + } + + return pb_encode_string(stream, bytes->bytes, bytes->size); +} + +static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + /* strnlen() is not always available, so just use a loop */ + size_t size = 0; + size_t max_size = field->data_size; + const char *p = (const char*)src; + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + max_size = (size_t)-1; + + if (src == NULL) + { + size = 0; /* Threat null pointer as an empty string */ + } + else + { + while (size < max_size && *p != '\0') + { + size++; + p++; + } + } + + return pb_encode_string(stream, (const uint8_t*)src, size); +} + +static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_t *field, const void *src) +{ + if (field->ptr == NULL) + PB_RETURN_ERROR(stream, "invalid field descriptor"); + + return pb_encode_submessage(stream, (const pb_field_t*)field->ptr, src); +} + diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 049a2b1d..93784c59 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -15,8 +15,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -option(MOCK_FRI "Use mock classes instead of the FRI Client Library" OFF) - # find dependencies find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) @@ -27,25 +25,9 @@ find_package(std_srvs REQUIRED) find_package(sensor_msgs REQUIRED) find_package(kuka_sunrise_interfaces REQUIRED) find_package(kroshu_ros2_core REQUIRED) +find_package(fri REQUIRED) -include_directories(include) - -if(NOT MOCK_FRI) - find_library(fri_client_library - libFRIClient.a - PATHS /home/rosdeveloper/Documents/fri_client_source/lib) - message("Using real fri lib") -else() - add_library(fri_client - src/fri_client_mock/friClientApplication_mock.cpp - src/fri_client_mock/friLBRClient_mock.cpp - src/fri_client_mock/friLBRCommand_mock.cpp - src/fri_client_mock/friLBRState_mock.cpp - src/fri_client_mock/friTransformationClient_mock.cpp - src/fri_client_mock/friUdpConnection_mock.cpp) - set(fri_client_library fri_client) - message("Using mock fri lib") -endif() +include_directories(include /home/rosdeveloper/ros2_ws/src/ros2_kuka_drivers/fri_client/include) add_library(internal SHARED @@ -85,8 +67,7 @@ add_executable(robot_control_node src/kuka_sunrise/robot_control_node.cpp) ament_target_dependencies(robot_control_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs sensor_msgs std_srvs kroshu_ros2_core) target_link_libraries(robot_control_node - robot_control_client - ${fri_client_library}) + robot_control_client fri::fri_client) add_executable(position_controller_node test/position_controller.cpp) @@ -116,10 +97,6 @@ install( ) if(BUILD_TESTING) - - # _ament_cmake_python_register_environment_hook() - - find_package(ament_cmake_copyright REQUIRED) find_package(ament_cmake_cppcheck REQUIRED) find_package(ament_cmake_pep257 REQUIRED) @@ -141,27 +118,14 @@ if(BUILD_TESTING) \"--single-version-externally-managed\" WORKING_DIRECTORY \"${PROJECT_SOURCE_DIR}\")" ) - file(GLOB fri_headers - LIST_DIRECTORIES FALSE - RELATIVE "${PROJECT_SOURCE_DIR}/include/fri_client" - include/fri_client/*) - - ament_copyright(--exclude ${fri_headers}) -# friClientApplication.h -# friClientIf.h -# friConnectionIf.h -# friException.h -# friLBRClient.h -# friLBRCommand.h -# friLBRState.h -# friTransformationClient.h -# friUdpConnection.h) + + ament_copyright() ament_cppcheck(--language=c++) ament_pep257() ament_flake8() ament_cpplint() ament_lint_cmake() - ament_uncrustify(--exclude ${fri_headers}) + ament_uncrustify() ament_xmllint() endif() diff --git a/kuka_sunrise_driver/include/fri_client/CPPLINT.cfg b/kuka_sunrise_driver/include/fri_client/CPPLINT.cfg deleted file mode 100644 index 8b4fa3ee..00000000 --- a/kuka_sunrise_driver/include/fri_client/CPPLINT.cfg +++ /dev/null @@ -1,17 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -# exclude all files in this directory -exclude_files=./* \ No newline at end of file diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp index 71527ac5..1043ba87 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp @@ -31,7 +31,7 @@ #include "rclcpp/strategies/allocator_memory_strategy.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" -#include "fri_client/friLBRClient.h" +#include "fri/friLBRClient.h" namespace kuka_sunrise { diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index b937a9bc..483595c6 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -23,7 +23,7 @@ #include "kuka_sunrise_interfaces/srv/set_int.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" -#include "fri_client/friLBRClient.h" +#include "fri/friLBRClient.h" namespace kuka_sunrise diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp index 754170d1..65298757 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp @@ -24,8 +24,8 @@ #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/set_bool.hpp" -#include "fri_client/friClientApplication.h" -#include "fri_client/friUdpConnection.h" +#include "fri/friClientApplication.h" +#include "fri/friUdpConnection.h" #include "kuka_sunrise/robot_control_client.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" #include "kuka_sunrise_interfaces/srv/get_state.hpp" diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp index 62e69f9c..fb0598fc 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp @@ -27,7 +27,7 @@ #include "std_msgs/msg/float64.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" -#include "fri_client/friLBRClient.h" +#include "fri/friLBRClient.h" namespace kuka_sunrise { diff --git a/kuka_sunrise_driver/src/fri_client_mock/CPPLINT.cfg b/kuka_sunrise_driver/src/fri_client_mock/CPPLINT.cfg deleted file mode 100644 index 75b122a3..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/CPPLINT.cfg +++ /dev/null @@ -1,17 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -# disable runtime/int checks for unsigned long long -filter=-runtime/int \ No newline at end of file diff --git a/kuka_sunrise_driver/src/fri_client_mock/friClientApplication_mock.cpp b/kuka_sunrise_driver/src/fri_client_mock/friClientApplication_mock.cpp deleted file mode 100644 index 9f4cc91e..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/friClientApplication_mock.cpp +++ /dev/null @@ -1,73 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "fri_client/friClientApplication.h" - -namespace KUKA -{ -namespace FRI -{ - -class IClient -{ -}; -class TransformationClient -{ -}; -class IConnection -{ -}; -struct ClientData -{ -}; - -ClientApplication::ClientApplication(IConnection & connection, IClient & client) -: _connection(connection), _robotClient(), _trafoClient(), _data() -{ - (void)client; -} - -ClientApplication::ClientApplication( - IConnection & connection, IClient & client, - TransformationClient & trafoClient) -: _connection(connection), _robotClient(), _trafoClient(), _data() -{ - (void)client; - (void)trafoClient; -} - -ClientApplication::~ClientApplication() -{ -} - -bool ClientApplication::connect(int port, const char * remoteHost) -{ - (void)port; - (void)remoteHost; - return false; -} - -void ClientApplication::disconnect() -{ - // only a mock -} - -bool ClientApplication::step() -{ - return false; -} - -} // namespace FRI - -} // namespace KUKA diff --git a/kuka_sunrise_driver/src/fri_client_mock/friLBRClient_mock.cpp b/kuka_sunrise_driver/src/fri_client_mock/friLBRClient_mock.cpp deleted file mode 100644 index 0fcf8f04..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/friLBRClient_mock.cpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "fri_client/friClientIf.h" -#include "fri_client/friLBRClient.h" - -namespace KUKA -{ -namespace FRI -{ - -struct ClientData -{ -}; - -LBRClient::LBRClient() -{ -} - -LBRClient::~LBRClient() -{ -} - -void LBRClient::onStateChange(ESessionState oldState, ESessionState newState) -{ - (void)oldState; - (void)newState; -} - -void LBRClient::monitor() -{ - // only a mock -} - -void LBRClient::waitForCommand() -{ - // only a mock -} - -void LBRClient::command() -{ - // only a mock -} - -ClientData * LBRClient::createData() -{ - return nullptr; -} - -} // namespace FRI - -} // namespace KUKA diff --git a/kuka_sunrise_driver/src/fri_client_mock/friLBRCommand_mock.cpp b/kuka_sunrise_driver/src/fri_client_mock/friLBRCommand_mock.cpp deleted file mode 100644 index 78f6d721..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/friLBRCommand_mock.cpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "fri_client/friLBRCommand.h" - -namespace KUKA -{ -namespace FRI -{ - -void LBRCommand::setJointPosition(const double * values) -{ - (void)values; -} - -void LBRCommand::setWrench(const double * wrench) -{ - (void)wrench; -} - -void LBRCommand::setTorque(const double * torques) -{ - (void)torques; -} - -void LBRCommand::setBooleanIOValue(const char * name, const bool value) -{ - (void)name; - (void)value; -} - -void LBRCommand::setDigitalIOValue(const char * name, const unsigned long long value) -{ - (void)name; - (void)value; -} - -void LBRCommand::setAnalogIOValue(const char * name, const double value) -{ - (void)name; - (void)value; -} - -} // namespace FRI - -} // namespace KUKA diff --git a/kuka_sunrise_driver/src/fri_client_mock/friLBRState_mock.cpp b/kuka_sunrise_driver/src/fri_client_mock/friLBRState_mock.cpp deleted file mode 100644 index 72c77051..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/friLBRState_mock.cpp +++ /dev/null @@ -1,141 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "fri_client/friClientIf.h" -#include "fri_client/friLBRState.h" - -namespace KUKA -{ -namespace FRI -{ - -struct _FRIMonitoringMessage -{ -}; - -LBRState::LBRState() -: _message() -{ -} - -double LBRState::getSampleTime() const -{ - return 0.0; -} - -ESessionState LBRState::getSessionState() const -{ - return IDLE; -} - -EConnectionQuality LBRState::getConnectionQuality() const -{ - return POOR; -} - -ESafetyState LBRState::getSafetyState() const -{ - return NORMAL_OPERATION; -} - -EOperationMode LBRState::getOperationMode() const -{ - return TEST_MODE_1; -} - -EDriveState LBRState::getDriveState() const -{ - return OFF; -} - -EClientCommandMode LBRState::getClientCommandMode() const -{ - return NO_COMMAND_MODE; -} - -EOverlayType LBRState::getOverlayType() const -{ - return NO_OVERLAY; -} - -EControlMode LBRState::getControlMode() const -{ - return NO_CONTROL; -} - -unsigned int LBRState::getTimestampSec() const -{ - return 0; -} - -unsigned int LBRState::getTimestampNanoSec() const -{ - return 0; -} - -const double * LBRState::getMeasuredJointPosition() const -{ - return nullptr; -} - -const double * LBRState::getCommandedJointPosition() const -{ - return nullptr; -} - -const double * LBRState::getMeasuredTorque() const -{ - return nullptr; -} - -const double * LBRState::getCommandedTorque() const -{ - return nullptr; -} - -const double * LBRState::getExternalTorque() const -{ - return nullptr; -} - -const double * LBRState::getIpoJointPosition() const -{ - return nullptr; -} - -double LBRState::getTrackingPerformance() const -{ - return 0.0; -} - -bool LBRState::getBooleanIOValue(const char * name) const -{ - (void)name; - return false; -} -unsigned long long LBRState::getDigitalIOValue(const char * name) const -{ - (void)name; - return 0; -} - -double LBRState::getAnalogIOValue(const char * name) const -{ - (void)name; - return 0.0; -} - -} // namespace FRI - -} // namespace KUKA diff --git a/kuka_sunrise_driver/src/fri_client_mock/friTransformationClient_mock.cpp b/kuka_sunrise_driver/src/fri_client_mock/friTransformationClient_mock.cpp deleted file mode 100644 index bcf9dbc8..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/friTransformationClient_mock.cpp +++ /dev/null @@ -1,110 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include "fri_client/friClientIf.h" -#include "fri_client/friTransformationClient.h" - -namespace KUKA -{ -namespace FRI -{ - -struct ClientData -{ -}; - -TransformationClient::TransformationClient() -: _data() -{ -} - -double TransformationClient::getSampleTime() const -{ - return 0.0; -} - -EConnectionQuality TransformationClient::getConnectionQuality() const -{ - return POOR; -} - -const std::vector & TransformationClient::getRequestedTransformationIDs() const -{ - return std::vector(); -} - -const unsigned int TransformationClient::getTimestampSec() const -{ - const unsigned int i = 0; - return i; -} - -const unsigned int TransformationClient::getTimestampNanoSec() const -{ - const unsigned int i = 0; - return i; -} - -void TransformationClient::setTransformation( - const char * transformationID, - const double transformationMatrix[3][4], - unsigned int timeSec, unsigned int timeNanoSec) -{ - (void)transformationID; - (void)transformationMatrix; - (void)timeSec; - (void)timeNanoSec; -} - -void TransformationClient::setBooleanIOValue(const char * name, const bool value) -{ - (void)name; - (void)value; -} - -void TransformationClient::setDigitalIOValue(const char * name, const unsigned long long value) -{ - (void)name; - (void)value; -} - -void TransformationClient::setAnalogIOValue(const char * name, const double value) -{ - (void)name; - (void)value; -} - -bool TransformationClient::getBooleanIOValue(const char * name) const -{ - (void)name; - return false; -} - -unsigned long long TransformationClient::getDigitalIOValue(const char * name) const -{ - (void)name; - return 0; -} - -double TransformationClient::getAnalogIOValue(const char * name) const -{ - (void)name; - return 0.0; -} - -} // namespace FRI - -} // namespace KUKA diff --git a/kuka_sunrise_driver/src/fri_client_mock/friUdpConnection_mock.cpp b/kuka_sunrise_driver/src/fri_client_mock/friUdpConnection_mock.cpp deleted file mode 100644 index bee4487e..00000000 --- a/kuka_sunrise_driver/src/fri_client_mock/friUdpConnection_mock.cpp +++ /dev/null @@ -1,64 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -namespace KUKA -{ -namespace FRI -{ - -UdpConnection::UdpConnection(unsigned int receiveTimeout) -: _udpSock(0), _receiveTimeout(receiveTimeout) -{ -} - -UdpConnection::~UdpConnection() -{ -} - -bool UdpConnection::open(int port, const char * controllerAddress) -{ - (void)port; - (void)controllerAddress; - return false; -} - -void UdpConnection::close() -{ - // only a mock -} - -bool UdpConnection::isOpen() const -{ - return false; -} - -int UdpConnection::receive(char * buffer, int maxSize) -{ - (void)buffer; - (void)maxSize; - return 0; -} - -bool UdpConnection::send(const char * buffer, int size) -{ - (void)buffer; - (void)size; - return false; -} - -} // namespace FRI - -} // namespace KUKA From 3d64b950e894c08dc963b1ea93a7e86012007632 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 22 Jun 2022 15:59:04 +0200 Subject: [PATCH 03/94] change to extended FRI client app --- fri_client/CMakeLists.txt | 15 +++++++++++++++ .../include/kuka_sunrise/robot_control_node.hpp | 2 +- .../src/kuka_sunrise/robot_control_node.cpp | 2 +- 3 files changed, 17 insertions(+), 2 deletions(-) diff --git a/fri_client/CMakeLists.txt b/fri_client/CMakeLists.txt index 48cc0829..87781e9d 100644 --- a/fri_client/CMakeLists.txt +++ b/fri_client/CMakeLists.txt @@ -66,10 +66,25 @@ else() ) endif() +file(GLOB private_headers + LIST_DIRECTORIES FALSE + RELATIVE "${PROJECT_SOURCE_DIR}" + src/friClientData.h + src/friCommandMessageEncoder.h + src/FRIMessages.pb.h + src/friMonitoringMessageDecoder.h + src/pb_frimessages_callbacks.h + ) + target_link_libraries(fri_client PRIVATE NanoPB::nanopb) +message(WARNING ${private_headers}) + ament_export_targets(fri_client HAS_LIBRARY_TARGET) +install(DIRECTORY include/fri DESTINATION include) +install(FILES ${private_headers} DESTINATION include) + install( TARGETS fri_client EXPORT fri_client diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp index 65298757..6a8b0c06 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp @@ -24,7 +24,7 @@ #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/set_bool.hpp" -#include "fri/friClientApplication.h" +#include "fri/HWIFClientApplication.hpp" #include "fri/friUdpConnection.h" #include "kuka_sunrise/robot_control_client.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp index 56917822..939020c4 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp @@ -106,7 +106,7 @@ RobotControlNode::on_cleanup(const rclcpp_lifecycle::State &) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControlNode::on_activate(const rclcpp_lifecycle::State &) { - client_application_ = std::make_unique(udp_connection_, *client_); + client_application_ = std::make_unique(udp_connection_, *client_); client_application_thread_ = std::make_unique(); auto run_app = [](void * robot_control_node) -> void * { From 5d622f966b753922ddb88aa08a68b8c8616d4da4 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 23 Jun 2022 15:26:55 +0200 Subject: [PATCH 04/94] add fri dependency --- fri_client/CMakeLists.txt | 2 -- kuka_sunrise_driver/package.xml | 2 ++ 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fri_client/CMakeLists.txt b/fri_client/CMakeLists.txt index 87781e9d..1ee57cde 100644 --- a/fri_client/CMakeLists.txt +++ b/fri_client/CMakeLists.txt @@ -78,8 +78,6 @@ file(GLOB private_headers target_link_libraries(fri_client PRIVATE NanoPB::nanopb) -message(WARNING ${private_headers}) - ament_export_targets(fri_client HAS_LIBRARY_TARGET) install(DIRECTORY include/fri DESTINATION include) diff --git a/kuka_sunrise_driver/package.xml b/kuka_sunrise_driver/package.xml index 35b93c7a..6787f60c 100644 --- a/kuka_sunrise_driver/package.xml +++ b/kuka_sunrise_driver/package.xml @@ -12,6 +12,8 @@ ament_cmake_python rosidl_default_generators + fri + rclcpp rclcpp_lifecycle std_msgs From be5fb888907f3d10ac10faea28f5fcfc136ed6d6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 24 Jun 2022 15:27:33 +0200 Subject: [PATCH 05/94] create hardware_interface from RobotControlClient --- kuka_sunrise_driver/CMakeLists.txt | 4 +- .../include/kuka_sunrise/robot_commander.hpp | 3 +- .../kuka_sunrise/robot_control_client.hpp | 41 ++++- .../kuka_sunrise/robot_control_node.hpp | 1 - .../include/kuka_sunrise/robot_observer.hpp | 5 +- kuka_sunrise_driver/package.xml | 21 +-- .../src/kuka_sunrise/robot_commander.cpp | 51 +++--- .../src/kuka_sunrise/robot_control_client.cpp | 159 +++++++++++++++++- .../src/kuka_sunrise/robot_control_node.cpp | 18 +- .../src/kuka_sunrise/robot_observer.cpp | 34 ++-- 10 files changed, 255 insertions(+), 82 deletions(-) diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 93784c59..2463eb45 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -26,6 +26,7 @@ find_package(sensor_msgs REQUIRED) find_package(kuka_sunrise_interfaces REQUIRED) find_package(kroshu_ros2_core REQUIRED) find_package(fri REQUIRED) +find_package(hardware_interface REQUIRED) include_directories(include /home/rosdeveloper/ros2_ws/src/ros2_kuka_drivers/fri_client/include) @@ -49,7 +50,8 @@ add_library(robot_control_client SHARED src/kuka_sunrise/robot_control_client.cpp src/kuka_sunrise/robot_observer.cpp src/kuka_sunrise/robot_commander.cpp) -ament_target_dependencies(robot_control_client kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs sensor_msgs std_srvs) +ament_target_dependencies(robot_control_client kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs sensor_msgs std_srvs hardware_interface) +target_link_libraries(robot_control_client fri::fri_client) add_library(configuration_manager SHARED src/kuka_sunrise/configuration_manager.cpp) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp index 1043ba87..70f97079 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp @@ -96,8 +96,7 @@ class RobotCommander : public ActivatableInterface { public: RobotCommander( - KUKA::FRI::LBRCommand & robot_command, const KUKA::FRI::LBRState & robot_state_, - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node); + KUKA::FRI::LBRCommand & robot_command, const KUKA::FRI::LBRState & robot_state_); void addBooleanOutputCommander(const std::string & name); void addDigitalOutputCommander(const std::string & name); void addAnalogOutputCommander(const std::string & name); diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index 483595c6..5cb96776 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -20,11 +20,17 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include +#include +#include "kuka_sunrise_interfaces/srv/set_int.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" #include "fri/friLBRClient.h" +#include "fri/HWIFClientApplication.hpp" +#include "fri/friUdpConnection.h" + +using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; namespace kuka_sunrise { @@ -32,10 +38,11 @@ namespace kuka_sunrise class RobotObserver; class RobotCommander; -class RobotControlClient : public KUKA::FRI::LBRClient, public ActivatableInterface +class RobotControlClient : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, + public ActivatableInterface { public: - explicit RobotControlClient(rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_); + //explicit RobotControlClient(); ~RobotControlClient(); bool activate(); bool deactivate(); @@ -45,15 +52,41 @@ class RobotControlClient : public KUKA::FRI::LBRClient, public ActivatableInterf virtual void waitForCommand(); virtual void command(); + CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; + CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; + CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; + CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; + + hardware_interface::return_type read( + const rclcpp::Time & time, + const rclcpp::Duration & period) override; + hardware_interface::return_type write( + const rclcpp::Time & time, + const rclcpp::Duration & period) override; + + std::vector export_state_interfaces() override; + std::vector export_command_interfaces() override; + private: std::unique_ptr robot_observer_; std::unique_ptr robot_commander_; - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; + // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; rclcpp::Service::SharedPtr set_receive_multiplier_service_; rclcpp::Clock ros_clock_; int receive_multiplier_; int receive_counter_; + + + // Dummy parameters + double hw_start_sec_, hw_stop_sec_, hw_slowdown_; + // Store the command for the simulated robot + std::vector hw_commands_, hw_states_; + std::vector hw_torques_, hw_effort_command_; + + KUKA::FRI::HWIFClientApplication client_application_; + KUKA::FRI::UdpConnection udp_connection_; + }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp index 6a8b0c06..79bc3756 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp @@ -59,7 +59,6 @@ class RobotControlNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat private: KUKA::FRI::UdpConnection udp_connection_; std::unique_ptr client_; - std::unique_ptr client_application_; std::unique_ptr client_application_thread_; std::atomic_bool close_requested_; diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp index fb0598fc..7e9de9af 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp @@ -72,8 +72,7 @@ class RobotObserver : public ActivatableInterface { public: RobotObserver( - const KUKA::FRI::LBRState & robot_state, - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node); + const KUKA::FRI::LBRState & robot_state); void addBooleanInputObserver(std::string name); void addDigitalInputObserver(std::string name); void addAnalogInputObserver(std::string name); @@ -85,7 +84,7 @@ class RobotObserver : public ActivatableInterface const KUKA::FRI::LBRState & robot_state_; sensor_msgs::msg::JointState joint_state_msg_; - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; + //rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr joint_state_publisher_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr diff --git a/kuka_sunrise_driver/package.xml b/kuka_sunrise_driver/package.xml index 6787f60c..b16b6ccd 100644 --- a/kuka_sunrise_driver/package.xml +++ b/kuka_sunrise_driver/package.xml @@ -13,22 +13,15 @@ rosidl_default_generators fri + rclcpp + rclcpp_lifecycle + std_msgs + std_srvs + sensor_msgs + kuka_sunrise_interfaces + kroshu_ros2_core - rclcpp - rclcpp_lifecycle - std_msgs - std_srvs - sensor_msgs - kuka_sunrise_interfaces - kroshu_ros2_core - - rclcpp - rclcpp_lifecycle - std_msgs - std_srvs - sensor_msgs rosidl_default_runtime - kuka_sunrise_interfaces ament_cmake_copyright ament_cmake_cppcheck diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp index f4d5f528..54bfbbd9 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp @@ -25,10 +25,9 @@ namespace kuka_sunrise RobotCommander::RobotCommander( KUKA::FRI::LBRCommand & robot_command, - const KUKA::FRI::LBRState & robot_state, - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node) + const KUKA::FRI::LBRState & robot_state) : robot_command_(robot_command), robot_state_(robot_state), torque_command_mode_(false), - robot_control_node_(robot_control_node), ros_clock_(RCL_ROS_TIME) + ros_clock_(RCL_ROS_TIME) { auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); qos.best_effort(); @@ -37,10 +36,6 @@ RobotCommander::RobotCommander( {this->commandReceivedCallback(msg);}; // TODO(resizoltan) use TLSFAllocator? implement static strategy for jointstatemsg? auto msg_strategy = std::make_shared>(); - joint_command_subscription_ = robot_control_node_->create_subscription< - sensor_msgs::msg::JointState>( - "lbr_joint_command", qos, callback, - rclcpp::SubscriptionOptions(), msg_strategy); auto command_srv_callback = [this]( std_srvs::srv::SetBool::Request::SharedPtr request, @@ -51,13 +46,17 @@ RobotCommander::RobotCommander( response->success = false; } }; - set_command_mode_service_ = robot_control_node_->create_service( - "set_command_mode", command_srv_callback); + + //TODO(Svastits): create service for command mode changes + /*set_command_mode_service_ = robot_control_node_->create_service( + "set_command_mode", command_srv_callback);*/ } void RobotCommander::addBooleanOutputCommander(const std::string & name) { - if (robot_control_node_->get_current_state().label() != "unconfigured") { + // TODO(Svastits): add to command interfaces + + /*if (robot_control_node_->get_current_state().label() != "unconfigured") { return; // TODO(resizoltan) handle other states } auto output_setter_func = [this](std::string name, bool value) -> void { @@ -67,12 +66,14 @@ void RobotCommander::addBooleanOutputCommander(const std::string & name) std::make_unique>( name, output_setter_func, is_active_, - robot_control_node_)); + robot_control_node_));*/ } void RobotCommander::addDigitalOutputCommander(const std::string & name) { - if (robot_control_node_->get_current_state().label() != "unconfigured") { + // TODO(Svastits): add to command interfaces + + /*if (robot_control_node_->get_current_state().label() != "unconfigured") { return; // TODO(resizoltan) handle other states } auto output_setter_func = [this](std::string name, uint64_t value) -> void { @@ -80,12 +81,14 @@ void RobotCommander::addDigitalOutputCommander(const std::string & name) }; output_subscriptions_.emplace_back( std::make_unique>( - name, output_setter_func, is_active_, robot_control_node_)); + name, output_setter_func, is_active_, robot_control_node_));*/ } void RobotCommander::addAnalogOutputCommander(const std::string & name) { - if (robot_control_node_->get_current_state().label() != "unconfigured") { + // TODO(Svastits): add to command interfaces + + /*if (robot_control_node_->get_current_state().label() != "unconfigured") { return; // TODO(resizoltan) handle other states } auto output_setter_func = [this](std::string name, double value) -> void { @@ -95,7 +98,7 @@ void RobotCommander::addAnalogOutputCommander(const std::string & name) std::make_unique>( name, output_setter_func, is_active_, - robot_control_node_)); + robot_control_node_));*/ } bool RobotCommander::setTorqueCommanding(bool is_torque_mode_active) @@ -113,17 +116,13 @@ void RobotCommander::updateCommand(const rclcpp::Time & stamp) std::unique_lock lk(m_); while (!joint_command_msg_ || joint_command_msg_->header.stamp != stamp) { if (!is_active_) { - RCLCPP_INFO( - robot_control_node_->get_logger(), - "robot commander deactivated, exiting updatecommand"); + printf("robot commander deactivated, exiting updatecommand\n"); return; } cv_.wait(lk); // check if wait has been interrupted by the robot manager if (!is_active_) { - RCLCPP_INFO( - robot_control_node_->get_logger(), - "robot commander deactivated, exiting updatecommand"); + printf("robot commander deactivated, exiting updatecommand\n"); return; } } @@ -131,9 +130,7 @@ void RobotCommander::updateCommand(const rclcpp::Time & stamp) if (torque_command_mode_) { if (joint_command_msg_->effort.empty()) { // raise some error/warning - RCLCPP_ERROR( - robot_control_node_->get_logger(), - "Effort of joint command msg is empty in torque command mode"); + printf("Effort of joint command msg is empty in torque command mode\n"); return; } const double * joint_torques_ = joint_command_msg_->effort.data(); @@ -142,9 +139,7 @@ void RobotCommander::updateCommand(const rclcpp::Time & stamp) } else { if (joint_command_msg_->position.empty()) { // raise some error/warning - RCLCPP_ERROR( - robot_control_node_->get_logger(), - "Position of joint command msg is empty in position command mode"); + printf("Position of joint command msg is empty in position command mode\n"); return; } const double * joint_positions_ = joint_command_msg_->position.data(); @@ -160,7 +155,7 @@ void RobotCommander::commandReceivedCallback(sensor_msgs::msg::JointState::Const { std::lock_guard lk(m_); if (!is_active_) { - RCLCPP_INFO(robot_control_node_->get_logger(), "commander not activated"); + printf("commander not activated\n"); return; } joint_command_msg_ = msg; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 27097586..78e97d94 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -20,10 +20,69 @@ namespace kuka_sunrise { +CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInfo & system_info) +{ + if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { + return CallbackReturn::ERROR; + } + hw_states_.resize(info_.joints.size()); + hw_commands_.resize(info_.joints.size()); + + robot_commander_ = std::make_unique(robotCommand(), robotState()); + robot_observer_ = std::make_unique(robotState()); + + for (const hardware_interface::ComponentInfo & joint : info_.joints) { + + if (joint.command_interfaces.size() != 1) { + RCLCPP_FATAL( + rclcpp::get_logger("RobotControlClient"), + "expecting exactly 1 command interface"); + return CallbackReturn::ERROR; + } + + // TODO(Svastits): enable effort interface too + if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION) { + RCLCPP_FATAL( + rclcpp::get_logger( + "RobotControlClient"), "expecting only POSITION command interface"); + return CallbackReturn::ERROR; + } + + if (joint.state_interfaces.size() != 1) { + RCLCPP_FATAL(rclcpp::get_logger("RobotControlClient"), "expecting exactly 1 state interface"); + return CallbackReturn::ERROR; + } + + if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) { + RCLCPP_FATAL( + rclcpp::get_logger( + "RobotControlClient"), "expecting only POSITION state interface"); + return CallbackReturn::ERROR; + } + } + + return CallbackReturn::SUCCESS; +} + +CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) +{ + return CallbackReturn::SUCCESS; +} -RobotControlClient::RobotControlClient( - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node) -: robot_control_node_(robot_control_node), receive_multiplier_(1), receive_counter_(0) +CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) +{ + return CallbackReturn::SUCCESS; +} + +CallbackReturn RobotControlClient::on_deactivate(const rclcpp_lifecycle::State &) +{ + + return CallbackReturn::SUCCESS; +} + + +/*RobotControlClient::RobotControlClient() +: receive_multiplier_(1), receive_counter_(0) { robot_observer_ = std::make_unique(robotState(), robot_control_node); robot_commander_ = std::make_unique( @@ -40,7 +99,7 @@ RobotControlClient::RobotControlClient( }; set_receive_multiplier_service_ = robot_control_node_->create_service< kuka_sunrise_interfaces::srv::SetInt>("set_receive_multiplier", command_srv_callback); -} +}*/ RobotControlClient::~RobotControlClient() { @@ -95,7 +154,7 @@ void RobotControlClient::command() bool RobotControlClient::setReceiveMultiplier(int receive_multiplier) { - if (robot_control_node_->get_current_state().label() == "inactive") { + if (1) { receive_multiplier_ = receive_multiplier; return true; } else { @@ -103,4 +162,94 @@ bool RobotControlClient::setReceiveMultiplier(int receive_multiplier) } } +hardware_interface::return_type RobotControlClient::read( + const rclcpp::Time &, + const rclcpp::Duration &) +{ + if (!is_active_) { + return hardware_interface::return_type::ERROR; + } + + if(!client_application_.client_app_read()) + { + RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Failed to read data from controller"); + return hardware_interface::return_type::ERROR; + } + + // get the position and efforts and share them with exposed state interfaces + const double* position = robotState().getMeasuredJointPosition(); + hw_states_.assign(position, position+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + const double* torque = robotState().getMeasuredTorque(); + hw_torques_.assign(torque, torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + // const double* external_torque = robotState().getExternalTorque(); + // TODO(Svastits): add external torque interface + + return hardware_interface::return_type::OK; +} + +hardware_interface::return_type RobotControlClient::write( + const rclcpp::Time &, + const rclcpp::Duration &) +{ + if (!is_active_) { + RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "Controller deactivated"); + return hardware_interface::return_type::ERROR; + } + + + client_application_.client_app_update(); + + for (size_t i = 0; i < info_.joints.size(); i++) { + RCLCPP_INFO( + rclcpp::get_logger( + "RobotControlClient"), "Got command %.5f for joint %ld!", hw_commands_[i], i); + } + + client_application_.client_app_write(); + + return hardware_interface::return_type::OK; +} + +std::vector RobotControlClient::export_state_interfaces() +{ + RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); + + std::vector state_interfaces; + for (size_t i = 0; i < info_.joints.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + info_.joints[i].name, + hardware_interface::HW_IF_POSITION, + &hw_states_[i])); + + state_interfaces.emplace_back( + hardware_interface::StateInterface( + info_.joints[i].name, + hardware_interface::HW_IF_EFFORT, + &hw_torques_[i])); + } + return state_interfaces; +} + +std::vector RobotControlClient::export_command_interfaces() +{ + RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_command_interfaces()"); + + std::vector command_interfaces; + for (size_t i = 0; i < info_.joints.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + info_.joints[i].name, + hardware_interface::HW_IF_POSITION, + &hw_commands_[i])); + + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + info_.joints[i].name, + hardware_interface::HW_IF_EFFORT, + &hw_effort_command_[i])); + } + return command_interfaces; +} + } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp index 939020c4..3736462a 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp @@ -51,10 +51,10 @@ RobotControlNode::RobotControlNode() void RobotControlNode::runClientApplication() { - client_application_->connect(30200, NULL); + //client_application_->connect(30200, NULL); bool success = true; while (success && !close_requested_.load()) { - success = client_application_->step(); + //success = client_application_->step(); if (client_->robotState().getSessionState() == KUKA::FRI::IDLE) { break; @@ -68,7 +68,7 @@ void RobotControlNode::runClientApplication() rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControlNode::on_configure(const rclcpp_lifecycle::State &) { - client_ = std::make_unique(this->shared_from_this()); + //client_ = std::make_unique(); // TODO(resizoltan) change stack size with setrlimit rlimit_stack? if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) { @@ -98,7 +98,7 @@ RobotControlNode::on_cleanup(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "munlockall error"); return ERROR; } - client_.reset(); + //client_.reset(); return SUCCESS; } @@ -106,7 +106,7 @@ RobotControlNode::on_cleanup(const rclcpp_lifecycle::State &) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControlNode::on_activate(const rclcpp_lifecycle::State &) { - client_application_ = std::make_unique(udp_connection_, *client_); + //client_application_ = std::make_unique(udp_connection_, *client_); client_application_thread_ = std::make_unique(); auto run_app = [](void * robot_control_node) -> void * { @@ -132,8 +132,8 @@ RobotControlNode::on_deactivate(const rclcpp_lifecycle::State &) close_requested_.store(true); pthread_join(*client_application_thread_, NULL); // TODO(resizoltan) can hang here, apply timeout close_requested_.store(false); - client_application_->disconnect(); - client_application_.reset(); + //client_application_->disconnect(); + //client_application_.reset(); client_application_thread_.reset(); return SUCCESS; } @@ -141,13 +141,13 @@ RobotControlNode::on_deactivate(const rclcpp_lifecycle::State &) bool RobotControlNode::activate() { this->ActivatableInterface::activate(); - return client_->activate(); + //return client_->activate(); } bool RobotControlNode::deactivate() { this->ActivatableInterface::deactivate(); - return client_->deactivate(); + //return client_->deactivate(); } } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp index b6c53a59..b1489740 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp @@ -25,7 +25,9 @@ namespace kuka_sunrise void RobotObserver::addBooleanInputObserver(std::string name) { - if (robot_control_node_->get_current_state().label() != "unconfigured") { + // TODO(Svastits): add to state interfaces + + /*if (robot_control_node_->get_current_state().label() != "unconfigured") { return; // TODO(resizoltan) handle other states } auto input_getter_func = [this](std::string name) -> bool { @@ -34,12 +36,14 @@ void RobotObserver::addBooleanInputObserver(std::string name) input_publishers_.emplace_back( std::make_unique>( name, - input_getter_func, robot_control_node_)); + input_getter_func, robot_control_node_));*/ } void RobotObserver::addDigitalInputObserver(std::string name) { - if (robot_control_node_->get_current_state().label() != "unconfigured") { + // TODO(Svastits): add to state interfaces + + /*if (robot_control_node_->get_current_state().label() != "unconfigured") { return; // TODO(resizoltan) handle other states } auto input_getter_func = [this](std::string name) -> uint64_t { @@ -48,12 +52,14 @@ void RobotObserver::addDigitalInputObserver(std::string name) input_publishers_.emplace_back( std::make_unique>( name, - input_getter_func, robot_control_node_)); + input_getter_func, robot_control_node_));*/ } void RobotObserver::addAnalogInputObserver(std::string name) { - if (robot_control_node_->get_current_state().label() != "unconfigured") { + // TODO(Svastits): add to state interfaces + + /*if (robot_control_node_->get_current_state().label() != "unconfigured") { return; // TODO(resizoltan) handle other states } auto input_getter_func = [this](std::string name) -> double { @@ -62,7 +68,7 @@ void RobotObserver::addAnalogInputObserver(std::string name) input_publishers_.emplace_back( std::make_unique>( name, - input_getter_func, robot_control_node_)); + input_getter_func, robot_control_node_));*/ } bool RobotObserver::activate() @@ -82,28 +88,26 @@ bool RobotObserver::deactivate() } RobotObserver::RobotObserver( - const KUKA::FRI::LBRState & robot_state, - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node) -: robot_state_(robot_state), robot_control_node_(robot_control_node) + const KUKA::FRI::LBRState & robot_state) +: robot_state_(robot_state) { joint_state_msg_.position.reserve(robot_state_.NUMBER_OF_JOINTS); joint_state_msg_.velocity.reserve(robot_state_.NUMBER_OF_JOINTS); joint_state_msg_.effort.reserve(robot_state_.NUMBER_OF_JOINTS); auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); qos.best_effort(); - joint_state_publisher_ = robot_control_node->create_publisher< - sensor_msgs::msg::JointState>("lbr_joint_state", 1); - tracking_performance_publisher_ = robot_control_node->create_publisher< - std_msgs::msg::Float64>("tracking_performance", qos); + // TODO(Svastits): add to state interface + /*tracking_performance_publisher_ = robot_control_node->create_publisher< + std_msgs::msg::Float64>("tracking_performance", qos);*/ } void RobotObserver::publishRobotState(const rclcpp::Time & stamp) { - if (robot_control_node_->get_current_state().label() != "inactive" && + /*if (robot_control_node_->get_current_state().label() != "inactive" && robot_control_node_->get_current_state().label() != "active") { return; // TODO(resizoltan) handle other states - } + }*/ joint_state_msg_.header.frame_id = "world"; joint_state_msg_.header.stamp = stamp; // TODO(resizoltan) catch exceptions From 909a977ecd636a25d375e324d31526c7b0d88105 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 27 Jun 2022 11:54:22 +0200 Subject: [PATCH 06/94] create plugin without commander and observer --- kuka_sunrise_driver/CMakeLists.txt | 2 + kuka_sunrise_driver/hardware_interface.xml | 8 ++ .../kuka_sunrise/robot_control_client.hpp | 18 ++- .../include/kuka_sunrise/robot_observer.hpp | 2 +- .../src/kuka_sunrise/robot_commander.cpp | 29 +---- .../src/kuka_sunrise/robot_control_client.cpp | 109 ++++++++---------- .../src/kuka_sunrise/robot_control_node.cpp | 21 ++-- 7 files changed, 85 insertions(+), 104 deletions(-) create mode 100644 kuka_sunrise_driver/hardware_interface.xml diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 2463eb45..94bb3f64 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -27,6 +27,7 @@ find_package(kuka_sunrise_interfaces REQUIRED) find_package(kroshu_ros2_core REQUIRED) find_package(fri REQUIRED) find_package(hardware_interface REQUIRED) +find_package(pluginlib REQUIRED) include_directories(include /home/rosdeveloper/ros2_ws/src/ros2_kuka_drivers/fri_client/include) @@ -83,6 +84,7 @@ add_executable(lifecycle_client_node test/lifecycle_client_test.cpp) ament_target_dependencies(lifecycle_client_node rclcpp rclcpp_lifecycle std_msgs) +pluginlib_export_plugin_description_file(hardware_interface hardware_interface.xml) install(TARGETS robot_manager robot_control_client robot_manager_node robot_control_node position_controller_node torque_controller_node lifecycle_client_node DESTINATION lib/${PROJECT_NAME}) diff --git a/kuka_sunrise_driver/hardware_interface.xml b/kuka_sunrise_driver/hardware_interface.xml new file mode 100644 index 00000000..fdaee7f2 --- /dev/null +++ b/kuka_sunrise_driver/hardware_interface.xml @@ -0,0 +1,8 @@ + + + + + ROS2 control hardware interface for KUKA LBR robots using the Fast Robot Interface (FRI). + + diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index 5cb96776..bbe7c107 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -17,6 +17,7 @@ #include #include +#include #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" @@ -35,20 +36,17 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface namespace kuka_sunrise { -class RobotObserver; -class RobotCommander; - class RobotControlClient : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, public ActivatableInterface { public: - //explicit RobotControlClient(); + RobotControlClient() + : client_application_(udp_connection_, *this) {} ~RobotControlClient(); bool activate(); bool deactivate(); bool setReceiveMultiplier(int receive_multiplier); - virtual void monitor(); virtual void waitForCommand(); virtual void command(); @@ -64,22 +62,18 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU const rclcpp::Time & time, const rclcpp::Duration & period) override; + void updateCommand(const rclcpp::Time & stamp); + std::vector export_state_interfaces() override; std::vector export_command_interfaces() override; private: - std::unique_ptr robot_observer_; - std::unique_ptr robot_commander_; - // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; rclcpp::Service::SharedPtr set_receive_multiplier_service_; rclcpp::Clock ros_clock_; int receive_multiplier_; int receive_counter_; - - // Dummy parameters - double hw_start_sec_, hw_stop_sec_, hw_slowdown_; // Store the command for the simulated robot std::vector hw_commands_, hw_states_; std::vector hw_torques_, hw_effort_command_; @@ -87,6 +81,8 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU KUKA::FRI::HWIFClientApplication client_application_; KUKA::FRI::UdpConnection udp_connection_; + bool torque_command_mode_ = false; + double tracking_performance_; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp index 7e9de9af..12c25895 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp @@ -84,7 +84,7 @@ class RobotObserver : public ActivatableInterface const KUKA::FRI::LBRState & robot_state_; sensor_msgs::msg::JointState joint_state_msg_; - //rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; + // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr joint_state_publisher_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp index 54bfbbd9..afe32763 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp @@ -47,7 +47,7 @@ RobotCommander::RobotCommander( } }; - //TODO(Svastits): create service for command mode changes + // TODO(Svastits): create service for command mode changes /*set_command_mode_service_ = robot_control_node_->create_service( "set_command_mode", command_srv_callback);*/ } @@ -113,18 +113,9 @@ bool RobotCommander::setTorqueCommanding(bool is_torque_mode_active) void RobotCommander::updateCommand(const rclcpp::Time & stamp) { - std::unique_lock lk(m_); - while (!joint_command_msg_ || joint_command_msg_->header.stamp != stamp) { - if (!is_active_) { - printf("robot commander deactivated, exiting updatecommand\n"); - return; - } - cv_.wait(lk); - // check if wait has been interrupted by the robot manager - if (!is_active_) { - printf("robot commander deactivated, exiting updatecommand\n"); - return; - } + if (!is_active_) { + printf("robot commander deactivated, exiting updatecommand\n"); + return; } if (torque_command_mode_) { @@ -151,22 +142,10 @@ void RobotCommander::updateCommand(const rclcpp::Time & stamp) } } -void RobotCommander::commandReceivedCallback(sensor_msgs::msg::JointState::ConstSharedPtr msg) -{ - std::lock_guard lk(m_); - if (!is_active_) { - printf("commander not activated\n"); - return; - } - joint_command_msg_ = msg; - cv_.notify_one(); -} bool RobotCommander::deactivate() { - std::lock_guard lk(m_); is_active_ = false; - cv_.notify_one(); // interrupt updateCommand() return true; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 78e97d94..6b2be817 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -15,24 +15,19 @@ #include #include "kuka_sunrise/robot_control_client.hpp" -#include "kuka_sunrise/robot_commander.hpp" -#include "kuka_sunrise/robot_observer.hpp" namespace kuka_sunrise { CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInfo & system_info) { +// TODO(Svastits): add parameter for command mode, receive multiplier etc if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; } hw_states_.resize(info_.joints.size()); hw_commands_.resize(info_.joints.size()); - robot_commander_ = std::make_unique(robotCommand(), robotState()); - robot_observer_ = std::make_unique(robotState()); - for (const hardware_interface::ComponentInfo & joint : info_.joints) { - if (joint.command_interfaces.size() != 1) { RCLCPP_FATAL( rclcpp::get_logger("RobotControlClient"), @@ -71,73 +66,38 @@ CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) { + client_application_.connect(30200, nullptr); return CallbackReturn::SUCCESS; } CallbackReturn RobotControlClient::on_deactivate(const rclcpp_lifecycle::State &) { - + client_application_.disconnect(); return CallbackReturn::SUCCESS; } - -/*RobotControlClient::RobotControlClient() -: receive_multiplier_(1), receive_counter_(0) -{ - robot_observer_ = std::make_unique(robotState(), robot_control_node); - robot_commander_ = std::make_unique( - robotCommand(), robotState(), - robot_control_node); - auto command_srv_callback = [this]( - kuka_sunrise_interfaces::srv::SetInt::Request::SharedPtr request, - kuka_sunrise_interfaces::srv::SetInt::Response::SharedPtr response) { - if (this->setReceiveMultiplier(request->data)) { - response->success = true; - } else { - response->success = false; - } - }; - set_receive_multiplier_service_ = robot_control_node_->create_service< - kuka_sunrise_interfaces::srv::SetInt>("set_receive_multiplier", command_srv_callback); -}*/ - RobotControlClient::~RobotControlClient() { - robot_commander_->deactivate(); } bool RobotControlClient::activate() { - // TODO(Svastits): activating the robot_observer should be moved to the on_activate function - // of the node! As of now, activating the driver nodes in themselves do not activate - // the observer, and the monitoring mode is not working on the ROS2 side - // (the publisher is not active, joint states are not sent) this->ActivatableInterface::activate(); - robot_commander_->activate(); - robot_observer_->activate(); return true; // TODO(resizoltan) check if successful } bool RobotControlClient::deactivate() { this->ActivatableInterface::deactivate(); - robot_commander_->deactivate(); - robot_observer_->deactivate(); return true; // TODO(resizoltan) check if successful } -void RobotControlClient::monitor() -{ - rclcpp::Time stamp = ros_clock_.now(); - robot_observer_->publishRobotState(stamp); -} - void RobotControlClient::waitForCommand() { + // TODO(Svastits): is this really the purpose of waitForCommand? rclcpp::Time stamp = ros_clock_.now(); - robot_observer_->publishRobotState(stamp); if (++receive_counter_ == receive_multiplier_) { - robot_commander_->updateCommand(stamp); + updateCommand(stamp); receive_counter_ = 0; } } @@ -145,19 +105,19 @@ void RobotControlClient::waitForCommand() void RobotControlClient::command() { rclcpp::Time stamp = ros_clock_.now(); - robot_observer_->publishRobotState(stamp); if (++receive_counter_ == receive_multiplier_) { - robot_commander_->updateCommand(stamp); + updateCommand(stamp); receive_counter_ = 0; } } bool RobotControlClient::setReceiveMultiplier(int receive_multiplier) { - if (1) { + if (!is_active_) { receive_multiplier_ = receive_multiplier; return true; } else { + printf("Receive multiplier cannot be set, if client is active\n"); return false; } } @@ -170,18 +130,20 @@ hardware_interface::return_type RobotControlClient::read( return hardware_interface::return_type::ERROR; } - if(!client_application_.client_app_read()) - { - RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Failed to read data from controller"); - return hardware_interface::return_type::ERROR; + if (!client_application_.client_app_read()) { + RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Failed to read data from controller"); + return hardware_interface::return_type::ERROR; } // get the position and efforts and share them with exposed state interfaces - const double* position = robotState().getMeasuredJointPosition(); - hw_states_.assign(position, position+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); - const double* torque = robotState().getMeasuredTorque(); - hw_torques_.assign(torque, torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + const double * position = robotState().getMeasuredJointPosition(); + hw_states_.assign(position, position + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + const double * torque = robotState().getMeasuredTorque(); + hw_torques_.assign(torque, torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + + tracking_performance_ = robotState().getTrackingPerformance(); // const double* external_torque = robotState().getExternalTorque(); + // hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); // TODO(Svastits): add external torque interface return hardware_interface::return_type::OK; @@ -196,7 +158,8 @@ hardware_interface::return_type RobotControlClient::write( return hardware_interface::return_type::ERROR; } - + // Call the appropriate callback for the actual state (e.g. updateCommand) + // this updates the command to be sent based on the output of the controller update client_application_.client_app_update(); for (size_t i = 0; i < info_.joints.size(); i++) { @@ -210,6 +173,29 @@ hardware_interface::return_type RobotControlClient::write( return hardware_interface::return_type::OK; } +void RobotControlClient::updateCommand(const rclcpp::Time &) +{ + if (!is_active_) { + printf("client deactivated, exiting updateCommand\n"); + return; + } + + if (torque_command_mode_) { + const double * joint_torques_ = hw_effort_command_.data(); + robotCommand().setJointPosition(robotState().getIpoJointPosition()); + robotCommand().setTorque(joint_torques_); + } else { + const double * joint_positions_ = hw_commands_.data(); + robotCommand().setJointPosition(joint_positions_); + } + // TODO(Svastits): setDigitalIOValue and setAnalogIOValue +/* + for (auto & output_subscription : output_subscriptions_) { + output_subscription->updateOutput(); + } + */ +} + std::vector RobotControlClient::export_state_interfaces() { RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); @@ -251,5 +237,12 @@ std::vector RobotControlClient::export_com } return command_interfaces; } - } // namespace kuka_sunrise + +#include "pluginlib/class_list_macros.hpp" + + +PLUGINLIB_EXPORT_CLASS( + kuka_sunrise::RobotControlClient, + hardware_interface::SystemInterface +) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp index 3736462a..d2123e41 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp @@ -51,10 +51,10 @@ RobotControlNode::RobotControlNode() void RobotControlNode::runClientApplication() { - //client_application_->connect(30200, NULL); + // client_application_->connect(30200, NULL); bool success = true; while (success && !close_requested_.load()) { - //success = client_application_->step(); + // success = client_application_->step(); if (client_->robotState().getSessionState() == KUKA::FRI::IDLE) { break; @@ -68,7 +68,7 @@ void RobotControlNode::runClientApplication() rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControlNode::on_configure(const rclcpp_lifecycle::State &) { - //client_ = std::make_unique(); + // client_ = std::make_unique(); // TODO(resizoltan) change stack size with setrlimit rlimit_stack? if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) { @@ -98,7 +98,7 @@ RobotControlNode::on_cleanup(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "munlockall error"); return ERROR; } - //client_.reset(); + // client_.reset(); return SUCCESS; } @@ -106,7 +106,8 @@ RobotControlNode::on_cleanup(const rclcpp_lifecycle::State &) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControlNode::on_activate(const rclcpp_lifecycle::State &) { - //client_application_ = std::make_unique(udp_connection_, *client_); + // client_application_ = std::make_unique + // (udp_connection_, *client_); client_application_thread_ = std::make_unique(); auto run_app = [](void * robot_control_node) -> void * { @@ -132,8 +133,8 @@ RobotControlNode::on_deactivate(const rclcpp_lifecycle::State &) close_requested_.store(true); pthread_join(*client_application_thread_, NULL); // TODO(resizoltan) can hang here, apply timeout close_requested_.store(false); - //client_application_->disconnect(); - //client_application_.reset(); + // client_application_->disconnect(); + // client_application_.reset(); client_application_thread_.reset(); return SUCCESS; } @@ -141,13 +142,15 @@ RobotControlNode::on_deactivate(const rclcpp_lifecycle::State &) bool RobotControlNode::activate() { this->ActivatableInterface::activate(); - //return client_->activate(); + // return client_->activate(); + return true; } bool RobotControlNode::deactivate() { this->ActivatableInterface::deactivate(); - //return client_->deactivate(); + // return client_->deactivate(); + return true; } } // namespace kuka_sunrise From 99df87c3202f933e4f89c4481988b35cc2910074 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 27 Jun 2022 16:45:12 +0200 Subject: [PATCH 07/94] add basic launch file --- kuka_sunrise_driver/launch/basic_launch.py | 41 ++++++++++++++++++++++ 1 file changed, 41 insertions(+) create mode 100644 kuka_sunrise_driver/launch/basic_launch.py diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py new file mode 100644 index 00000000..b4221f48 --- /dev/null +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -0,0 +1,41 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch_ros.actions import Node + +def load_file(absolute_file_path): + # package_path = get_package_share_directory(package_name) + # absolute_file_path = os.path.join(package_path, file_path) + + try: + with open(absolute_file_path, 'r') as file: + return file.read() + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + return None + + +def generate_launch_description(): + controller_config = get_package_share_directory('urdflbriiwa7') + "/config/iiwa_ros2_controller_config.yaml" + + robot_description_config = load_file("/home/rosdeveloper/ros2_ws/src/urdflbriiwa7/urdf/urdflbriiwa7.urdf") + robot_description = {'robot_description' : robot_description_config} + + return LaunchDescription([ + Node( + package='controller_manager', + executable='ros2_control_node', + parameters=[robot_description, controller_config], + ), + Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + ), + Node( + package="controller_manager", + executable="spawner", + arguments=["forward_command_controller_position", "--controller-manager", "/controller_manager"], + ), + ]) \ No newline at end of file From 71d151a9da1cda4e95a468aaef1b1bc0c38ead2c Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 27 Jun 2022 17:45:45 +0200 Subject: [PATCH 08/94] ci to foxy, add dependency --- .github/workflows/industrial_ci.yml | 2 +- kuka_sunrise_driver/package.xml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/industrial_ci.yml b/.github/workflows/industrial_ci.yml index 6d7f7f40..f1f6bfde 100644 --- a/.github/workflows/industrial_ci.yml +++ b/.github/workflows/industrial_ci.yml @@ -39,7 +39,7 @@ jobs: TEST_COVERAGE: true UPSTREAM_WORKSPACE: 'github:kroshu/kroshu_ros2_core#master' CMAKE_ARGS: '-DMOCK_FRI=ON' - ROS_DISTRO: foxy + ROS_DISTRO: humble env: CCACHE_DIR: /github/home/.ccache # Directory for ccache (and how we enable ccache in industrial_ci) EVENT_NAME: ${{ github.event_name }} diff --git a/kuka_sunrise_driver/package.xml b/kuka_sunrise_driver/package.xml index b16b6ccd..687bac10 100644 --- a/kuka_sunrise_driver/package.xml +++ b/kuka_sunrise_driver/package.xml @@ -20,6 +20,7 @@ sensor_msgs kuka_sunrise_interfaces kroshu_ros2_core + hardware_interface rosidl_default_runtime From ddfd0ebed1de22a09ed60d4f215c0a573fbe8810 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 28 Jun 2022 10:39:04 +0200 Subject: [PATCH 09/94] fix launch files --- kuka_sunrise_driver/launch/basic_launch.py | 6 +----- kuka_sunrise_driver/launch/kuka_sunrise.launch.py | 14 ++++---------- 2 files changed, 5 insertions(+), 15 deletions(-) diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index b4221f48..5f3d9abb 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -6,9 +6,6 @@ from launch_ros.actions import Node def load_file(absolute_file_path): - # package_path = get_package_share_directory(package_name) - # absolute_file_path = os.path.join(package_path, file_path) - try: with open(absolute_file_path, 'r') as file: return file.read() @@ -18,8 +15,7 @@ def load_file(absolute_file_path): def generate_launch_description(): controller_config = get_package_share_directory('urdflbriiwa7') + "/config/iiwa_ros2_controller_config.yaml" - - robot_description_config = load_file("/home/rosdeveloper/ros2_ws/src/urdflbriiwa7/urdf/urdflbriiwa7.urdf") + robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") robot_description = {'robot_description' : robot_description_config} return LaunchDescription([ diff --git a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py index a82f6c79..f01aa433 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py @@ -15,21 +15,15 @@ from launch import LaunchDescription import launch.actions -import launch.substitutions import launch_ros.actions def generate_launch_description(): return LaunchDescription([ - launch.actions.DeclareLaunchArgument( - 'node_prefix', - default_value=[''], - description='prefix for node names'), launch_ros.actions.LifecycleNode( - package='kuka_sunrise', executable='robot_manager_node', output='screen', - name=[launch.substitutions.LaunchConfiguration('node_prefix'), 'robot_manager'], - parameters=[{'controller_ip': ''}]), + namespace = '', package='kuka_sunrise', executable='robot_manager_node', output='screen', + name=['robot_manager'], parameters=[{'controller_ip': ''}]), launch_ros.actions.LifecycleNode( - package='kuka_sunrise', executable='robot_control_node', output='screen', - name=[launch.substitutions.LaunchConfiguration('node_prefix'), 'robot_control']) + namespace = '', package='kuka_sunrise', executable='robot_control_node', output='screen', + name=['robot_control']) ]) From 528787861b8f42062a6ca9132d927cb4583a56d6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 28 Jun 2022 10:39:41 +0200 Subject: [PATCH 10/94] activate interface of client --- kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 6b2be817..bfb891e7 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -67,12 +67,14 @@ CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) { client_application_.connect(30200, nullptr); + activate(); return CallbackReturn::SUCCESS; } CallbackReturn RobotControlClient::on_deactivate(const rclcpp_lifecycle::State &) { client_application_.disconnect(); + deactivate(); return CallbackReturn::SUCCESS; } From f2bee6610619495da04adbc0cb1acaeb8ad99fa6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 28 Jun 2022 11:06:39 +0200 Subject: [PATCH 11/94] port launch files to humble --- .../launch/GECI_for_RSI.launch.py | 1 + .../launch/keyboard_guided_robot.launch.py | 20 ++++++++++--------- .../launch/kinect_driver_arm_tracking.py | 1 + .../launch/kuka_sunrise.launch.py | 1 - 4 files changed, 13 insertions(+), 10 deletions(-) diff --git a/kuka_sunrise_control/teleop_guided_robot/launch/GECI_for_RSI.launch.py b/kuka_sunrise_control/teleop_guided_robot/launch/GECI_for_RSI.launch.py index 07f964f0..f9549100 100644 --- a/kuka_sunrise_control/teleop_guided_robot/launch/GECI_for_RSI.launch.py +++ b/kuka_sunrise_control/teleop_guided_robot/launch/GECI_for_RSI.launch.py @@ -52,6 +52,7 @@ def generate_launch_description(): robot_config_file = get_package_share_directory('robot_control') + "/config/kr6.yaml" joint_controller = launch_ros.actions.LifecycleNode( + namespace="", package='robot_control', executable='interpolating_controller', output='both', arguments=['--ros-args', '--log-level', 'info'], parameters=[robot_config_file], name='joint_controller', remappings=[('measured_joint_state', 'rsi_joint_state'), diff --git a/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py b/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py index 3f45aa92..7cc2b804 100644 --- a/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py +++ b/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py @@ -21,6 +21,7 @@ def generate_launch_description(): + robot_config_file = get_package_share_directory('robot_control') + "/config/lbr_iiwa.yaml" kuka_sunrise_dir = get_package_share_directory('kuka_sunrise') kuka_sunrise_interface = IncludeLaunchDescription( @@ -28,24 +29,25 @@ def generate_launch_description(): ) joint_controller = launch_ros.actions.LifecycleNode( - package='robot_control', node_executable='joint_controller', output='screen', - node_name='joint_controller', remappings=[('measured_joint_state', 'lbr_joint_state'), - ('joint_command', 'lbr_joint_command')] + namespace="", + package='robot_control', executable='interpolating_controller', output='screen', + parameters=[robot_config_file], name='joint_controller', + remappings=[('measured_joint_state', 'lbr_joint_state'), + ('joint_command', 'lbr_joint_command')] ) keyboard_control = launch_ros.actions.LifecycleNode( - package='teleop_guided_robot', node_executable='keyboard_control', output='screen', - node_name='keyboard_control' + namespace="", name='keyboard_control', + package='teleop_guided_robot', executable='keyboard_control', output='screen' ) system_manager = launch_ros.actions.LifecycleNode( - package='teleop_guided_robot', node_executable='system_manager', output='screen', - node_name='system_manager' + namespace="", name='system_manager', + package='teleop_guided_robot', executable='system_manager', output='screen' ) """ key_teleop = launch_ros.actions.Node( - package='key_teleop', node_executable='key_teleop', output='screen', - node_name='key_teleop') + package='key_teleop', executable='key_teleop', output='screen', name='key_teleop') """ return LaunchDescription([ kuka_sunrise_interface, diff --git a/kuka_sunrise_control/teleop_guided_robot/launch/kinect_driver_arm_tracking.py b/kuka_sunrise_control/teleop_guided_robot/launch/kinect_driver_arm_tracking.py index dc520d1c..0c2494be 100644 --- a/kuka_sunrise_control/teleop_guided_robot/launch/kinect_driver_arm_tracking.py +++ b/kuka_sunrise_control/teleop_guided_robot/launch/kinect_driver_arm_tracking.py @@ -59,6 +59,7 @@ def generate_launch_description(): ) joint_controller = launch_ros.actions.LifecycleNode( + namespace="", package='robot_control', executable='rate_scaled_controller', output='both', arguments=['--ros-args', '--log-level', 'info'], parameters=[robot_config_file, {'reference_rate': 12.0}], diff --git a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py index f01aa433..a4a0405c 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py @@ -14,7 +14,6 @@ from launch import LaunchDescription -import launch.actions import launch_ros.actions From 47db3a49de5597c5b4831b400c05220bd1ee9dcd Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 28 Jun 2022 15:56:02 +0200 Subject: [PATCH 12/94] interface count fix, add config file --- kuka_sunrise_driver/CMakeLists.txt | 3 +++ kuka_sunrise_driver/config/forward_controller.yaml | 12 ++++++++++++ kuka_sunrise_driver/launch/basic_launch.py | 6 ++++-- .../src/kuka_sunrise/robot_control_client.cpp | 8 ++++---- 4 files changed, 23 insertions(+), 6 deletions(-) create mode 100644 kuka_sunrise_driver/config/forward_controller.yaml diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 94bb3f64..371214c7 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -92,6 +92,9 @@ install(TARGETS robot_manager robot_control_client robot_manager_node robot_cont install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) +install(DIRECTORY config + DESTINATION share/${PROJECT_NAME}) + install(DIRECTORY include/kuka_sunrise/internal DESTINATION include/kuka_sunrise) install( TARGETS internal diff --git a/kuka_sunrise_driver/config/forward_controller.yaml b/kuka_sunrise_driver/config/forward_controller.yaml new file mode 100644 index 00000000..20a25bd9 --- /dev/null +++ b/kuka_sunrise_driver/config/forward_controller.yaml @@ -0,0 +1,12 @@ +forward_command_controller_position: + ros__parameters: + joints: + - URDFLBRiiwa7Joint1 + - URDFLBRiiwa7Joint2 + - URDFLBRiiwa7Joint3 + - URDFLBRiiwa7Joint4 + - URDFLBRiiwa7Joint5 + - URDFLBRiiwa7Joint6 + - URDFLBRiiwa7Joint7 + interface_name: position + diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index 5f3d9abb..7116faae 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -15,6 +15,7 @@ def load_file(absolute_file_path): def generate_launch_description(): controller_config = get_package_share_directory('urdflbriiwa7') + "/config/iiwa_ros2_controller_config.yaml" + forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") robot_description = {'robot_description' : robot_description_config} @@ -27,11 +28,12 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager", "--load-only"] ), Node( package="controller_manager", executable="spawner", - arguments=["forward_command_controller_position", "--controller-manager", "/controller_manager"], + arguments=["forward_command_controller_position", "--controller-manager", "/controller_manager", "--load-only"], + parameters=[forward_controller_config] ), ]) \ No newline at end of file diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index bfb891e7..45db6211 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -28,10 +28,10 @@ CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInf hw_commands_.resize(info_.joints.size()); for (const hardware_interface::ComponentInfo & joint : info_.joints) { - if (joint.command_interfaces.size() != 1) { + if (joint.command_interfaces.size() != 2) { RCLCPP_FATAL( rclcpp::get_logger("RobotControlClient"), - "expecting exactly 1 command interface"); + "expecting exactly 2 command interface"); return CallbackReturn::ERROR; } @@ -43,8 +43,8 @@ CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInf return CallbackReturn::ERROR; } - if (joint.state_interfaces.size() != 1) { - RCLCPP_FATAL(rclcpp::get_logger("RobotControlClient"), "expecting exactly 1 state interface"); + if (joint.state_interfaces.size() != 2) { + RCLCPP_FATAL(rclcpp::get_logger("RobotControlClient"), "expecting exactly 2 state interface"); return CallbackReturn::ERROR; } From 0c0d8cfc667a528766bbdeab1b2832172ae57c58 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 29 Jun 2022 14:43:52 +0200 Subject: [PATCH 13/94] fix node name, add rviz to launch --- .../config/forward_controller.yaml | 2 +- kuka_sunrise_driver/launch/basic_launch.py | 24 +++++++++++++++---- .../src/kuka_sunrise/robot_control_client.cpp | 3 +++ 3 files changed, 24 insertions(+), 5 deletions(-) diff --git a/kuka_sunrise_driver/config/forward_controller.yaml b/kuka_sunrise_driver/config/forward_controller.yaml index 20a25bd9..5621c023 100644 --- a/kuka_sunrise_driver/config/forward_controller.yaml +++ b/kuka_sunrise_driver/config/forward_controller.yaml @@ -1,4 +1,4 @@ -forward_command_controller_position: +/forward_command_controller_position: ros__parameters: joints: - URDFLBRiiwa7Joint1 diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index 7116faae..4a68ee37 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -19,21 +19,37 @@ def generate_launch_description(): robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") robot_description = {'robot_description' : robot_description_config} + rviz_config_file = os.path.join( + get_package_share_directory('urdflbriiwa7'), 'launch', 'urdf.rviz') + return LaunchDescription([ Node( package='controller_manager', executable='ros2_control_node', - parameters=[robot_description, controller_config], + parameters=[robot_description, controller_config] ), Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager", "--load-only"] + arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--stopped"] ), Node( package="controller_manager", executable="spawner", - arguments=["forward_command_controller_position", "--controller-manager", "/controller_manager", "--load-only"], - parameters=[forward_controller_config] + arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", + get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml", "--stopped"] + ), + # Node( + # package="rviz2", + # executable="rviz2", + # name="rviz2", + # output="log", + # arguments=["-d", rviz_config_file], + # ), + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + output='both', + parameters=[robot_description] ), ]) \ No newline at end of file diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 45db6211..7db66e67 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -66,6 +66,7 @@ CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) { + // TODO(Svastits): check success client_application_.connect(30200, nullptr); activate(); return CallbackReturn::SUCCESS; @@ -200,6 +201,8 @@ void RobotControlClient::updateCommand(const rclcpp::Time &) std::vector RobotControlClient::export_state_interfaces() { + + // TODO(Svastits): add FRI state interface RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); std::vector state_interfaces; From f75bd2084f67e5657dd5c1cbadebc2d131da357f Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 30 Jun 2022 15:12:57 +0200 Subject: [PATCH 14/94] add sunrise_control_node --- kuka_sunrise_driver/CMakeLists.txt | 8 +++- .../kuka_sunrise/robot_control_client.hpp | 1 + kuka_sunrise_driver/launch/basic_launch.py | 4 +- .../src/kuka_sunrise/robot_control_client.cpp | 2 + .../src/kuka_sunrise/robot_manager_node.cpp | 37 +++++++------- .../src/kuka_sunrise/sunrise_control_node.cpp | 48 +++++++++++++++++++ 6 files changed, 79 insertions(+), 21 deletions(-) create mode 100644 kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 371214c7..8bfc6b9f 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -28,6 +28,7 @@ find_package(kroshu_ros2_core REQUIRED) find_package(fri REQUIRED) find_package(hardware_interface REQUIRED) find_package(pluginlib REQUIRED) +find_package(controller_manager) include_directories(include /home/rosdeveloper/ros2_ws/src/ros2_kuka_drivers/fri_client/include) @@ -72,6 +73,11 @@ ament_target_dependencies(robot_control_node kuka_sunrise_interfaces rclcpp rclc target_link_libraries(robot_control_node robot_control_client fri::fri_client) + +add_executable(sunrise_control_node + src/kuka_sunrise/sunrise_control_node.cpp) +ament_target_dependencies(sunrise_control_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle controller_manager) + add_executable(position_controller_node test/position_controller.cpp) ament_target_dependencies(position_controller_node rclcpp sensor_msgs) @@ -86,7 +92,7 @@ ament_target_dependencies(lifecycle_client_node rclcpp rclcpp_lifecycle std_msgs pluginlib_export_plugin_description_file(hardware_interface hardware_interface.xml) -install(TARGETS robot_manager robot_control_client robot_manager_node robot_control_node position_controller_node torque_controller_node lifecycle_client_node +install(TARGETS robot_manager robot_control_client robot_manager_node robot_control_node position_controller_node torque_controller_node lifecycle_client_node sunrise_control_node DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index bbe7c107..7fad4ed4 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -83,6 +83,7 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU bool torque_command_mode_ = false; double tracking_performance_; + int fri_state_; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index 4a68ee37..d0706782 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -24,8 +24,8 @@ def generate_launch_description(): return LaunchDescription([ Node( - package='controller_manager', - executable='ros2_control_node', + package='kuka_sunrise', + executable='sunrise_control_node', parameters=[robot_description, controller_config] ), Node( diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 7db66e67..72fe55d3 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -145,6 +145,8 @@ hardware_interface::return_type RobotControlClient::read( hw_torques_.assign(torque, torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); tracking_performance_ = robotState().getTrackingPerformance(); + fri_state_ = robotState().getSessionState(); + // const double* external_torque = robotState().getExternalTorque(); // hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); // TODO(Svastits): add external torque interface diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 91e387f6..37dd93a9 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -58,12 +58,14 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) { auto result = SUCCESS; - if (!requestRobotControlNodeStateTransition( + /*if (!requestRobotControlNodeStateTransition( lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) { RCLCPP_ERROR(get_logger(), "could not configure robot control node"); return FAILURE; - } + }*/ + + // TODO(Svastits): configure HWInterface and controllers (currently done from launch file after loading) // If this fails, the node should be restarted, with different parameter values // Therefore exceptions are not caught @@ -105,12 +107,12 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) { - if (!requestRobotControlNodeStateTransition( + /*if (!requestRobotControlNodeStateTransition( lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) { RCLCPP_ERROR(get_logger(), "could not clean up robot control node"); return ERROR; - } + }*/ if (robot_manager_->isConnected() && !robot_manager_->disconnect()) { RCLCPP_ERROR(get_logger(), "could not disconnect"); @@ -139,12 +141,13 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) return SUCCESS; } - if (!requestRobotControlNodeStateTransition( + // TODO(Svasits): unload controllers, destroy HWInterface + /*if (!requestRobotControlNodeStateTransition( lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)) { RCLCPP_ERROR(get_logger(), "could not shut down control"); return ERROR; - } + }*/ return SUCCESS; } @@ -165,12 +168,20 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } - if (!requestRobotControlNodeStateTransition( + /*if (!requestRobotControlNodeStateTransition( lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) { RCLCPP_ERROR(get_logger(), "could not activate"); return FAILURE; - } + }*/ + + // TODO(Svastits): + // 1. activate HWInterface (blocks CM until connect is successful) + // 2. start FRI -> monitoring mode -> states are available + // 3. activate joint state broadcaster + // 4. activate (commanding) controller + // 5. this->activate() (=activate control) + if (!robot_manager_->startFRI()) { RCLCPP_ERROR(get_logger(), "could not start fri"); @@ -229,11 +240,6 @@ bool RobotManagerNode::activate() return false; } - if (!setRobotControlNodeCommandState(true)) { - RCLCPP_ERROR(get_logger(), "could not set command state"); - return false; - } - if (!robot_manager_->activateControl()) { // TODO(resizoltan) check robot control node state first this->ActivatableInterface::deactivate(); @@ -259,11 +265,6 @@ bool RobotManagerNode::deactivate() } this->ActivatableInterface::deactivate(); - if (!setRobotControlNodeCommandState(false)) { - // TODO(resizoltan) out of sync - RCLCPP_ERROR(get_logger(), "could not set command state"); - return false; - } std_msgs::msg::Bool command_state; command_state.data = false; command_state_changed_publisher_->publish(command_state); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp new file mode 100644 index 00000000..61995cf8 --- /dev/null +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -0,0 +1,48 @@ +// Copyright 2022 Ãron Svastits +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include "controller_manager/controller_manager.hpp" +#include "rclcpp/rclcpp.hpp" + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto executor = std::make_shared(); + auto controller_manager = std::make_shared(executor, "controller_manager"); + + std::thread control_loop([controller_manager]() { + const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); + + // TODO(Svastits): wait for FRI state changed + while (rclcpp::ok()) { + controller_manager->read(controller_manager->now(), dt); // Blocking until state received + controller_manager->update(controller_manager->now(), dt); + controller_manager->write(controller_manager->now(), dt); + } + }); + + executor->add_node(controller_manager); + + executor->spin(); + control_loop.join(); + + // shutdown + rclcpp::shutdown(); + + return 0; +} From b488edc9e49ec8243a44eb668afa8050d313f6ab Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 1 Jul 2022 11:24:51 +0200 Subject: [PATCH 15/94] initial activation logic without parameters with debug logs, read fails --- kuka_sunrise_driver/CMakeLists.txt | 3 +- .../kuka_sunrise/robot_manager_node.hpp | 4 + kuka_sunrise_driver/launch/basic_launch.py | 16 ++-- .../launch/kuka_sunrise_control.launch.py | 44 +++++++++ .../kuka_sunrise/configuration_manager.cpp | 6 ++ .../src/kuka_sunrise/robot_control_client.cpp | 5 +- .../src/kuka_sunrise/robot_manager_node.cpp | 93 ++++++++++--------- .../src/kuka_sunrise/sunrise_control_node.cpp | 1 + 8 files changed, 118 insertions(+), 54 deletions(-) create mode 100644 kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 8bfc6b9f..60278c6d 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -29,6 +29,7 @@ find_package(fri REQUIRED) find_package(hardware_interface REQUIRED) find_package(pluginlib REQUIRED) find_package(controller_manager) +find_package(controller_manager_msgs) include_directories(include /home/rosdeveloper/ros2_ws/src/ros2_kuka_drivers/fri_client/include) @@ -62,7 +63,7 @@ ament_target_dependencies(configuration_manager kuka_sunrise_interfaces rclcpp r add_executable(robot_manager_node src/kuka_sunrise/robot_manager_node.cpp) -ament_target_dependencies(robot_manager_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle kroshu_ros2_core) +ament_target_dependencies(robot_manager_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle kroshu_ros2_core controller_manager_msgs) target_link_libraries(robot_manager_node robot_manager configuration_manager) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index ea430f79..22c1bdff 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -25,6 +25,8 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" #include "std_msgs/msg/bool.hpp" +#include "controller_manager_msgs/srv/set_hardware_component_state.hpp" +#include "controller_manager_msgs/srv/configure_start_controller.hpp" #include "kuka_sunrise/robot_manager.hpp" #include "kuka_sunrise/configuration_manager.hpp" @@ -64,6 +66,8 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat rclcpp::Client::SharedPtr change_robot_control_state_client_; rclcpp::Client::SharedPtr set_parameter_client_; rclcpp::Client::SharedPtr set_commanding_state_client_; + rclcpp::Client::SharedPtr change_hardware_state_client_; + rclcpp::Client::SharedPtr change_controller_state_client_; rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp::Service::SharedPtr change_robot_commanding_state_service_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index d0706782..3a3ac43a 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -37,15 +37,15 @@ def generate_launch_description(): package="controller_manager", executable="spawner", arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", - get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml", "--stopped"] + forward_controller_config, "--stopped"] + ), + Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_config_file], ), - # Node( - # package="rviz2", - # executable="rviz2", - # name="rviz2", - # output="log", - # arguments=["-d", rviz_config_file], - # ), Node( package='robot_state_publisher', executable='robot_state_publisher', diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py new file mode 100644 index 00000000..0fab410f --- /dev/null +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -0,0 +1,44 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch_ros.actions import Node +from launch_ros.actions import LifecycleNode + +def load_file(absolute_file_path): + try: + with open(absolute_file_path, 'r') as file: + return file.read() + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + return None + + +def generate_launch_description(): + controller_config = get_package_share_directory('urdflbriiwa7') + "/config/iiwa_ros2_controller_config.yaml" + forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" + robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") + robot_description = {'robot_description' : robot_description_config} + + return LaunchDescription([ + Node( + package='kuka_sunrise', + executable='sunrise_control_node', + parameters=[robot_description, controller_config] + ), + LifecycleNode( + namespace = '', package='kuka_sunrise', executable='robot_manager_node', output='screen', + name=['robot_manager'], parameters=[{'controller_ip': ''}] + ), + Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--stopped"] + ), + Node( + package="controller_manager", + executable="spawner", + arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", + forward_controller_config, "--stopped"] + ) + ]) \ No newline at end of file diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index fd81c693..6a73084f 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -64,6 +64,7 @@ ConfigurationManager::ConfigurationManager( bool ConfigurationManager::onCommandModeChangeRequest(const std::string & command_mode) const { + return true; if (command_mode == "position") { if (!setCommandMode("position")) { return false; @@ -95,6 +96,7 @@ bool ConfigurationManager::onCommandModeChangeRequest(const std::string & comman bool ConfigurationManager::onControlModeChangeRequest(const std::string & control_mode) const { + return true; if (control_mode == "position") { return robot_manager_->setPositionControlMode(); } else if (control_mode == "joint_impedance") { @@ -116,6 +118,7 @@ bool ConfigurationManager::onControlModeChangeRequest(const std::string & contro bool ConfigurationManager::onJointStiffnessChangeRequest( const std::vector & joint_stiffness) { + return true; if (joint_stiffness.size() != 7) { RCLCPP_ERROR( robot_manager_node_->get_logger(), @@ -135,6 +138,7 @@ bool ConfigurationManager::onJointStiffnessChangeRequest( bool ConfigurationManager::onJointDampingChangeRequest(const std::vector & joint_damping) { + return true; if (joint_damping.size() != 7) { RCLCPP_ERROR( robot_manager_node_->get_logger(), @@ -153,6 +157,7 @@ bool ConfigurationManager::onJointDampingChangeRequest(const std::vector bool ConfigurationManager::onSendPeriodChangeRequest(const int & send_period) const { + return true; if (send_period < 1 || send_period > 100) { RCLCPP_ERROR( robot_manager_node_->get_logger(), @@ -167,6 +172,7 @@ bool ConfigurationManager::onSendPeriodChangeRequest(const int & send_period) co bool ConfigurationManager::onReceiveMultiplierChangeRequest(const int & receive_multiplier) const { + return true; if (receive_multiplier < 1) { RCLCPP_ERROR(robot_manager_node_->get_logger(), "Receive multiplier must be >=1"); return false; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 72fe55d3..39dffe69 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -66,9 +66,12 @@ CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) { + RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activating client\n"); // TODO(Svastits): check success - client_application_.connect(30200, nullptr); + if(!client_application_.connect(30200, nullptr)) + RCLCPP_ERROR(rclcpp::get_logger("HWIF"),"could not connect"); activate(); + RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activated client"); return CallbackReturn::SUCCESS; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 37dd93a9..332b70c0 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -37,6 +37,10 @@ RobotManagerNode::RobotManagerNode() "robot_control/change_state", qos.get_rmw_qos_profile(), cbg_); set_commanding_state_client_ = this->create_client( "robot_control/set_commanding_state", qos.get_rmw_qos_profile(), cbg_); + change_hardware_state_client_ = this->create_client( + "controller_manager/set_hardware_component_state", qos.get_rmw_qos_profile(), cbg_); + change_controller_state_client_ = this->create_client( + "controller_manager/configure_and_start_controller", qos.get_rmw_qos_profile(), cbg_); auto command_srv_callback = [this]( std_srvs::srv::SetBool::Request::SharedPtr request, std_srvs::srv::SetBool::Response::SharedPtr response) { @@ -57,16 +61,9 @@ RobotManagerNode::RobotManagerNode() rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) { + printf("logging\n"); auto result = SUCCESS; - /*if (!requestRobotControlNodeStateTransition( - lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) - { - RCLCPP_ERROR(get_logger(), "could not configure robot control node"); - return FAILURE; - }*/ - // TODO(Svastits): configure HWInterface and controllers (currently done from launch file after loading) - // If this fails, the node should be restarted, with different parameter values // Therefore exceptions are not caught if (!configuration_manager_) { @@ -74,7 +71,6 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) std::dynamic_pointer_cast( this->shared_from_this()), robot_manager_); } - const char * controller_ip = this->get_parameter("controller_ip").as_string().c_str(); if (!robot_manager_->isConnected()) { if (!robot_manager_->connect(controller_ip, 30000)) { @@ -85,6 +81,8 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "Robot manager is connected in inactive state"); return ERROR; } + + RCLCPP_ERROR(get_logger(), "connected"); // TODO(resizoltan) get IO configuration if (result == SUCCESS) { @@ -107,13 +105,6 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) { - /*if (!requestRobotControlNodeStateTransition( - lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) - { - RCLCPP_ERROR(get_logger(), "could not clean up robot control node"); - return ERROR; - }*/ - if (robot_manager_->isConnected() && !robot_manager_->disconnect()) { RCLCPP_ERROR(get_logger(), "could not disconnect"); return ERROR; @@ -142,13 +133,6 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) } // TODO(Svasits): unload controllers, destroy HWInterface - /*if (!requestRobotControlNodeStateTransition( - lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)) - { - RCLCPP_ERROR(get_logger(), "could not shut down control"); - return ERROR; - }*/ - return SUCCESS; } @@ -159,6 +143,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "not connected"); return ERROR; } + RCLCPP_ERROR(get_logger(), "activating"); auto send_period_ms = static_cast(this->get_parameter("send_period_ms").as_int()); auto receive_multiplier = static_cast(this->get_parameter("receive_multiplier").as_int()); @@ -168,34 +153,54 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } - /*if (!requestRobotControlNodeStateTransition( - lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) - { - RCLCPP_ERROR(get_logger(), "could not activate"); - return FAILURE; - }*/ - - // TODO(Svastits): - // 1. activate HWInterface (blocks CM until connect is successful) - // 2. start FRI -> monitoring mode -> states are available - // 3. activate joint state broadcaster - // 4. activate (commanding) controller - // 5. this->activate() (=activate control) + RCLCPP_ERROR(get_logger(), "set FRI config"); + // Activate hardware interface + auto hw_request = std::make_shared(); + hw_request->name = "iiwa_hardware"; + hw_request->target_state.label = "active"; + auto hw_response = kuka_sunrise::sendRequest( + change_hardware_state_client_, hw_request, 0, 2000); + if (!hw_response || !hw_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not activate hardware interface"); + return FAILURE; + } + RCLCPP_ERROR(get_logger(), "activated HWIF"); + // Start FRI (in monitoring mode) if (!robot_manager_->startFRI()) { RCLCPP_ERROR(get_logger(), "could not start fri"); - if (!requestRobotControlNodeStateTransition( - lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) - { - RCLCPP_ERROR( - get_logger(), - "Control node remained active, restart is needed"); - return ERROR; - } return FAILURE; } + RCLCPP_ERROR(get_logger(), "started FRI"); + + // Activate joint state broadcaster + auto controller_request = std::make_shared(); + controller_request->name = "joint_state_broadcaster"; + auto controller_response = kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not activate broadcaster"); + return FAILURE; + } + + RCLCPP_ERROR(get_logger(), "activated joint state broadcaster"); + + // Activate forward_command_controller + // TODO(Svastits): add parameter for controller name + controller_request->name = "forward_command_controller_position"; + controller_response = kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not activate controller"); + return FAILURE; + } + + // Start commanding mode + if (!activate()) + return FAILURE; + command_state_changed_publisher_->on_activate(); return SUCCESS; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 61995cf8..b1a055e9 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -31,6 +31,7 @@ int main(int argc, char** argv) // TODO(Svastits): wait for FRI state changed while (rclcpp::ok()) { controller_manager->read(controller_manager->now(), dt); // Blocking until state received + printf("AFTER READ\n"); controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); } From 95139870e4673d47c60646efcd96228c9c8907b8 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 4 Jul 2022 11:45:36 +0200 Subject: [PATCH 16/94] working driver (parameters still missing) --- .../kuka_sunrise/robot_control_client.hpp | 4 ++-- .../launch/kuka_sunrise_control.launch.py | 4 ++-- .../src/kuka_sunrise/robot_control_client.cpp | 18 +++++++++--------- .../src/kuka_sunrise/robot_manager_node.cpp | 9 +++------ .../src/kuka_sunrise/sunrise_control_node.cpp | 1 - 5 files changed, 16 insertions(+), 20 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index 7fad4ed4..4dec2aff 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -71,8 +71,8 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; rclcpp::Service::SharedPtr set_receive_multiplier_service_; rclcpp::Clock ros_clock_; - int receive_multiplier_; - int receive_counter_; + int receive_multiplier_ = 1; + int receive_counter_ = 0; // Store the command for the simulated robot std::vector hw_commands_, hw_states_; diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 0fab410f..c1a6b878 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -33,12 +33,12 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--stopped"] + arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--load-only"] ), Node( package="controller_manager", executable="spawner", arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", - forward_controller_config, "--stopped"] + forward_controller_config, "--load-only"] ) ]) \ No newline at end of file diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 39dffe69..88c5386a 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -26,6 +26,8 @@ CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInf } hw_states_.resize(info_.joints.size()); hw_commands_.resize(info_.joints.size()); + hw_torques_.resize(info_.joints.size()); + hw_effort_command_.resize(info_.joints.size()); for (const hardware_interface::ComponentInfo & joint : info_.joints) { if (joint.command_interfaces.size() != 2) { @@ -66,10 +68,12 @@ CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) { - RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activating client\n"); - // TODO(Svastits): check success + RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activating client"); if(!client_application_.connect(30200, nullptr)) + { RCLCPP_ERROR(rclcpp::get_logger("HWIF"),"could not connect"); + return CallbackReturn::FAILURE; + } activate(); RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activated client"); return CallbackReturn::SUCCESS; @@ -133,6 +137,8 @@ hardware_interface::return_type RobotControlClient::read( const rclcpp::Duration &) { if (!is_active_) { + RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Controller not active"); + std::this_thread::sleep_for(std::chrono::milliseconds(50)); return hardware_interface::return_type::ERROR; } @@ -149,11 +155,11 @@ hardware_interface::return_type RobotControlClient::read( tracking_performance_ = robotState().getTrackingPerformance(); fri_state_ = robotState().getSessionState(); + // RCLCPP_INFO(rclcpp::get_logger("ClientApplication"), "FRI state: %i", fri_state_); // const double* external_torque = robotState().getExternalTorque(); // hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); // TODO(Svastits): add external torque interface - return hardware_interface::return_type::OK; } @@ -170,12 +176,6 @@ hardware_interface::return_type RobotControlClient::write( // this updates the command to be sent based on the output of the controller update client_application_.client_app_update(); - for (size_t i = 0; i < info_.joints.size(); i++) { - RCLCPP_INFO( - rclcpp::get_logger( - "RobotControlClient"), "Got command %.5f for joint %ld!", hw_commands_[i], i); - } - client_application_.client_app_write(); return hardware_interface::return_type::OK; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 332b70c0..86c353e7 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -61,7 +61,6 @@ RobotManagerNode::RobotManagerNode() rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) { - printf("logging\n"); auto result = SUCCESS; // TODO(Svastits): configure HWInterface and controllers (currently done from launch file after loading) // If this fails, the node should be restarted, with different parameter values @@ -81,8 +80,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "Robot manager is connected in inactive state"); return ERROR; } - - RCLCPP_ERROR(get_logger(), "connected"); + RCLCPP_INFO(get_logger(), "Successfully connected to FRI"); // TODO(resizoltan) get IO configuration if (result == SUCCESS) { @@ -196,13 +194,12 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "Could not activate controller"); return FAILURE; } - + RCLCPP_ERROR(get_logger(), "activated controller"); + command_state_changed_publisher_->on_activate(); // Start commanding mode if (!activate()) return FAILURE; - command_state_changed_publisher_->on_activate(); - return SUCCESS; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index b1a055e9..61995cf8 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -31,7 +31,6 @@ int main(int argc, char** argv) // TODO(Svastits): wait for FRI state changed while (rclcpp::ok()) { controller_manager->read(controller_manager->now(), dt); // Blocking until state received - printf("AFTER READ\n"); controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); } From c9468ef44bda956217bb6d7c4c27052ed843e880 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 4 Jul 2022 11:54:34 +0200 Subject: [PATCH 17/94] update package.xml, TODO-s --- kuka_sunrise_driver/package.xml | 1 + kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp | 1 + kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp | 4 +++- 3 files changed, 5 insertions(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/package.xml b/kuka_sunrise_driver/package.xml index 687bac10..2929acce 100644 --- a/kuka_sunrise_driver/package.xml +++ b/kuka_sunrise_driver/package.xml @@ -21,6 +21,7 @@ kuka_sunrise_interfaces kroshu_ros2_core hardware_interface + controller_manager rosidl_default_runtime diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 86c353e7..e1a7f859 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -306,6 +306,7 @@ bool RobotManagerNode::setRobotControlNodeCommandState(bool active) void RobotManagerNode::handleControlEndedError() { // TODO(Svastits): deactivate managers by internal control ended error + // currently only the ActivatableInterface is deactivated RCLCPP_INFO(get_logger(), "control ended"); deactivate(); } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 61995cf8..d223851f 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -28,7 +28,9 @@ int main(int argc, char** argv) std::thread control_loop([controller_manager]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); - // TODO(Svastits): wait for FRI state changed + // TODO(Svastits): wait for FRI state changed?? + // TODO(Svastits): sync controller start state with robot pose at startup + // currently if robot is not in candle, speed limit is exceeded at startup while (rclcpp::ok()) { controller_manager->read(controller_manager->now(), dt); // Blocking until state received controller_manager->update(controller_manager->now(), dt); From 37a7cd65e55e2e26e540168ec349c0aeff4c2cd4 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 11 Jul 2022 12:40:46 +0200 Subject: [PATCH 18/94] add command interface and controller to manage FRI timing --- kuka_controllers/CMakeLists.txt | 53 +++++++++++++ kuka_controllers/controller_plugins.xml | 7 ++ .../kuka_controllers/timing_controller.hpp | 58 ++++++++++++++ kuka_controllers/package.xml | 22 ++++++ kuka_controllers/src/timing_controller.cpp | 77 +++++++++++++++++++ .../kuka_sunrise/robot_control_client.hpp | 4 +- .../launch/kuka_sunrise_control.launch.py | 5 ++ .../src/kuka_sunrise/robot_control_client.cpp | 34 ++++---- kuka_sunrise_interfaces/package.xml | 2 +- 9 files changed, 247 insertions(+), 15 deletions(-) create mode 100644 kuka_controllers/CMakeLists.txt create mode 100644 kuka_controllers/controller_plugins.xml create mode 100644 kuka_controllers/include/kuka_controllers/timing_controller.hpp create mode 100644 kuka_controllers/package.xml create mode 100644 kuka_controllers/src/timing_controller.cpp diff --git a/kuka_controllers/CMakeLists.txt b/kuka_controllers/CMakeLists.txt new file mode 100644 index 00000000..82035442 --- /dev/null +++ b/kuka_controllers/CMakeLists.txt @@ -0,0 +1,53 @@ +cmake_minimum_required(VERSION 3.5) +project(kuka_controllers) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra) +endif() + +find_package(ament_cmake REQUIRED) +find_package(controller_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) + +include_directories(include) + +add_library(${PROJECT_NAME} SHARED + src/timing_controller.cpp) + +target_include_directories(${PROJECT_NAME} PRIVATE + include +) + +ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface +) + +pluginlib_export_plugin_description_file(controller_interface controller_plugins.xml) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install(DIRECTORY include/ + DESTINATION include +) + +install(FILES controller_plugins.xml + DESTINATION share/${PROJECT_NAME} +) + +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) + +ament_export_include_directories( + include +) + +ament_export_libraries( + ${PROJECT_NAME} +) + +ament_package() diff --git a/kuka_controllers/controller_plugins.xml b/kuka_controllers/controller_plugins.xml new file mode 100644 index 00000000..d569d811 --- /dev/null +++ b/kuka_controllers/controller_plugins.xml @@ -0,0 +1,7 @@ + + + + This controller sets the receive multiplier of the hardware interface + + + diff --git a/kuka_controllers/include/kuka_controllers/timing_controller.hpp b/kuka_controllers/include/kuka_controllers/timing_controller.hpp new file mode 100644 index 00000000..2e161eea --- /dev/null +++ b/kuka_controllers/include/kuka_controllers/timing_controller.hpp @@ -0,0 +1,58 @@ +// Copyright 2022 Ãron Svastits +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License.------------------------------------------------------------------- + + +#ifndef KUKA_CONTROLLERS__TIMING_CONTROLLER_HPP_ +#define KUKA_CONTROLLERS__TIMING_CONTROLLER_HPP_ + +#include +#include +#include + +#include "controller_interface/controller_interface.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp/duration.hpp" + + +namespace kuka_controllers +{ +class TimingController : public controller_interface::ControllerInterface +{ +public: + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + + controller_interface::return_type update( + const rclcpp::Time & time, + const rclcpp::Duration & period) override; + + controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) + override; + + controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) + override; + + controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) + override; + + controller_interface::CallbackReturn on_init() override; + +private: + int receive_multiplier_ = 1; + bool resend_multiplier_ = true; +}; +} // namespace kuka_controllers +#endif // KUKA_CONTROLLERS__TIMING_CONTROLLER_HPP_ diff --git a/kuka_controllers/package.xml b/kuka_controllers/package.xml new file mode 100644 index 00000000..476078d4 --- /dev/null +++ b/kuka_controllers/package.xml @@ -0,0 +1,22 @@ + + + + kuka_controllers + 0.0.0 + Controller for managing the timing of the FRI hardware interface + + Aron Svastits + + Apache 2.0 + + ament_cmake + + controller_interface + lifecycle_msgs + pluginlib + rclcpp_lifecycle + + + ament_cmake + + diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp new file mode 100644 index 00000000..0e69c972 --- /dev/null +++ b/kuka_controllers/src/timing_controller.cpp @@ -0,0 +1,77 @@ +// Copyright 2022 Ãron Svastits +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License.------------------------------------------------------------------- + +#include "kuka_controllers/timing_controller.hpp" + +namespace kuka_controllers +{ +controller_interface::CallbackReturn TimingController::on_init() +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::InterfaceConfiguration TimingController::command_interface_configuration() +const +{ + controller_interface::InterfaceConfiguration config; + config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + config.names.push_back("timing/receive_multiplier"); + return config; +} + +controller_interface::InterfaceConfiguration TimingController::state_interface_configuration() const +{ + // TODO(Svastits): create service to get multiplier changes (or perpaps parameter??) + // and set resend_multiplier_ to true in the callback + return controller_interface::InterfaceConfiguration{controller_interface:: + interface_configuration_type::NONE}; +} + +controller_interface::CallbackReturn +TimingController::on_configure(const rclcpp_lifecycle::State &) +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn +TimingController::on_activate(const rclcpp_lifecycle::State &) +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn +TimingController::on_deactivate(const rclcpp_lifecycle::State &) +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::return_type TimingController::update( + const rclcpp::Time &, + const rclcpp::Duration &) +{ + // TODO(Svastits): disable changes if HWIF is active + if (resend_multiplier_) { + command_interfaces_[0].set_value(receive_multiplier_); + resend_multiplier_ = false; + } + return controller_interface::return_type::OK; +} + +} // namespace kuka_controllers + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + kuka_controllers::TimingController, + controller_interface::ControllerInterface) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index 4dec2aff..f3414584 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -71,7 +71,9 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; rclcpp::Service::SharedPtr set_receive_multiplier_service_; rclcpp::Clock ros_clock_; - int receive_multiplier_ = 1; + + // Command interface must be of type double, but controller can set only integers + double receive_multiplier_ = 1; int receive_counter_ = 0; // Store the command for the simulated robot diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index c1a6b878..98891164 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -40,5 +40,10 @@ def generate_launch_description(): executable="spawner", arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", forward_controller_config, "--load-only"] + ), + Node( + package="controller_manager", + executable="spawner", + arguments=["timing_controller", "-c", "/controller_manager"] ) ]) \ No newline at end of file diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 88c5386a..a865c1cb 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -21,6 +21,7 @@ namespace kuka_sunrise CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInfo & system_info) { // TODO(Svastits): add parameter for command mode, receive multiplier etc + if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; } @@ -37,11 +38,17 @@ CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInf return CallbackReturn::ERROR; } - // TODO(Svastits): enable effort interface too if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION) { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting only POSITION command interface"); + "RobotControlClient"), "expecting POSITION command interface as first"); + return CallbackReturn::ERROR; + } + + if (joint.command_interfaces[1].name != hardware_interface::HW_IF_EFFORT) { + RCLCPP_FATAL( + rclcpp::get_logger( + "RobotControlClient"), "expecting EFFORT command interface as second"); return CallbackReturn::ERROR; } @@ -53,9 +60,17 @@ CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInf if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting only POSITION state interface"); + "RobotControlClient"), "expecting POSITION state interface as first"); return CallbackReturn::ERROR; } + + if (joint.state_interfaces[1].name != hardware_interface::HW_IF_EFFORT) { + RCLCPP_FATAL( + rclcpp::get_logger( + "RobotControlClient"), "expecting EFFORT state interface as second"); + return CallbackReturn::ERROR; + } + // TODO(Svastits): add external torque interface to URDF and check it here } return CallbackReturn::SUCCESS; @@ -121,16 +136,6 @@ void RobotControlClient::command() } } -bool RobotControlClient::setReceiveMultiplier(int receive_multiplier) -{ - if (!is_active_) { - receive_multiplier_ = receive_multiplier; - return true; - } else { - printf("Receive multiplier cannot be set, if client is active\n"); - return false; - } -} hardware_interface::return_type RobotControlClient::read( const rclcpp::Time &, @@ -232,6 +237,9 @@ std::vector RobotControlClient::export_com RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_command_interfaces()"); std::vector command_interfaces; + + command_interfaces.emplace_back( + hardware_interface::CommandInterface("timing","receive_multiplier", &receive_multiplier_)); for (size_t i = 0; i < info_.joints.size(); i++) { command_interfaces.emplace_back( hardware_interface::CommandInterface( diff --git a/kuka_sunrise_interfaces/package.xml b/kuka_sunrise_interfaces/package.xml index c551f6b9..20a38525 100644 --- a/kuka_sunrise_interfaces/package.xml +++ b/kuka_sunrise_interfaces/package.xml @@ -5,7 +5,7 @@ 0.0.0 TODO: Package description rosdeveloper - TODO: License declaration + Apache 2.0 ament_cmake rosidl_default_generators From e1ccb7f49c108a6474ca041681ef9849375b12b6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 11 Jul 2022 15:58:10 +0200 Subject: [PATCH 19/94] add fri state broadcaster --- kuka_controllers/CMakeLists.txt | 5 +- kuka_controllers/controller_plugins.xml | 5 ++ .../robot_state_broadcaster.hpp | 61 ++++++++++++++ kuka_controllers/package.xml | 2 +- .../src/robot_state_broadcaster.cpp | 79 +++++++++++++++++++ kuka_controllers/src/timing_controller.cpp | 4 +- .../kuka_sunrise/robot_control_client.hpp | 2 +- .../launch/kuka_sunrise_control.launch.py | 5 ++ .../src/kuka_sunrise/robot_control_client.cpp | 3 + .../src/kuka_sunrise/sunrise_control_node.cpp | 15 +++- 10 files changed, 173 insertions(+), 8 deletions(-) create mode 100644 kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp create mode 100644 kuka_controllers/src/robot_state_broadcaster.cpp diff --git a/kuka_controllers/CMakeLists.txt b/kuka_controllers/CMakeLists.txt index 82035442..81c2cc1a 100644 --- a/kuka_controllers/CMakeLists.txt +++ b/kuka_controllers/CMakeLists.txt @@ -14,13 +14,14 @@ find_package(rclcpp_lifecycle REQUIRED) include_directories(include) add_library(${PROJECT_NAME} SHARED - src/timing_controller.cpp) + src/timing_controller.cpp + src/robot_state_broadcaster.cpp) target_include_directories(${PROJECT_NAME} PRIVATE include ) -ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface +ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface std_msgs ) pluginlib_export_plugin_description_file(controller_interface controller_plugins.xml) diff --git a/kuka_controllers/controller_plugins.xml b/kuka_controllers/controller_plugins.xml index d569d811..546dfd24 100644 --- a/kuka_controllers/controller_plugins.xml +++ b/kuka_controllers/controller_plugins.xml @@ -4,4 +4,9 @@ This controller sets the receive multiplier of the hardware interface + + + This broadcaster publishes the state changes of the FRI + + diff --git a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp new file mode 100644 index 00000000..bb5acdbe --- /dev/null +++ b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp @@ -0,0 +1,61 @@ +// Copyright 2022 Ãron Svastits +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License.------------------------------------------------------------------- + + +#ifndef KUKA_CONTROLLERS__ROBOT_STATE_BROADCASTER_HPP_ +#define KUKA_CONTROLLERS__ROBOT_STATE_BROADCASTER_HPP_ + +#include +#include +#include + +#include "controller_interface/controller_interface.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "std_msgs/msg/int32.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp/duration.hpp" + + +namespace kuka_controllers +{ +class RobotStateBroadcaster : public controller_interface::ControllerInterface +{ +public: + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + + controller_interface::return_type update( + const rclcpp::Time & time, + const rclcpp::Duration & period) override; + + controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) + override; + + controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) + override; + + controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) + override; + + controller_interface::CallbackReturn on_init() override; + +private: + int fri_state_ = 0; + bool resend_state_ = true; + rclcpp::Publisher::SharedPtr fri_state_publisher_; + std_msgs::msg::Int32 state_msg_; +}; +} // namespace kuka_controllers +#endif // KUKA_CONTROLLERS__ROBOT_STATE_BROADCASTER_HPP_ diff --git a/kuka_controllers/package.xml b/kuka_controllers/package.xml index 476078d4..c060961a 100644 --- a/kuka_controllers/package.xml +++ b/kuka_controllers/package.xml @@ -12,9 +12,9 @@ ament_cmake controller_interface - lifecycle_msgs pluginlib rclcpp_lifecycle + std_msgs ament_cmake diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp new file mode 100644 index 00000000..78819f91 --- /dev/null +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -0,0 +1,79 @@ +// Copyright 2022 Ãron Svastits +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License.------------------------------------------------------------------- + +#include "kuka_controllers/robot_state_broadcaster.hpp" + +namespace kuka_controllers +{ +controller_interface::CallbackReturn RobotStateBroadcaster::on_init() +{ + // TODO(Svastits): choose appropriate QoS settings for late joiners + fri_state_publisher_ = get_node()->create_publisher( + "fri_state", rclcpp::SystemDefaultsQoS()); + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::InterfaceConfiguration RobotStateBroadcaster::command_interface_configuration() +const +{ + return controller_interface::InterfaceConfiguration{controller_interface:: + interface_configuration_type::NONE}; +} + +controller_interface::InterfaceConfiguration RobotStateBroadcaster::state_interface_configuration() +const +{ + controller_interface::InterfaceConfiguration config; + config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + config.names.push_back("state/fri_state"); + return config; +} + +controller_interface::CallbackReturn +RobotStateBroadcaster::on_configure(const rclcpp_lifecycle::State &) +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn +RobotStateBroadcaster::on_activate(const rclcpp_lifecycle::State &) +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn +RobotStateBroadcaster::on_deactivate(const rclcpp_lifecycle::State &) +{ + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::return_type RobotStateBroadcaster::update( + const rclcpp::Time &, + const rclcpp::Duration &) +{ + state_msg_.data = state_interfaces_[0].get_value(); + if (fri_state_ != state_msg_.data) { + fri_state_ = state_msg_.data; + fri_state_publisher_->publish(state_msg_); + } + return controller_interface::return_type::OK; +} + +} // namespace kuka_controllers + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + kuka_controllers::RobotStateBroadcaster, + controller_interface::ControllerInterface) diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp index 0e69c972..858b40d1 100644 --- a/kuka_controllers/src/timing_controller.cpp +++ b/kuka_controllers/src/timing_controller.cpp @@ -18,6 +18,8 @@ namespace kuka_controllers { controller_interface::CallbackReturn TimingController::on_init() { + // TODO(Svastits): create service to get multiplier changes (or perpaps parameter??) + // and set resend_multiplier_ to true in the callback return controller_interface::CallbackReturn::SUCCESS; } @@ -32,8 +34,6 @@ const controller_interface::InterfaceConfiguration TimingController::state_interface_configuration() const { - // TODO(Svastits): create service to get multiplier changes (or perpaps parameter??) - // and set resend_multiplier_ to true in the callback return controller_interface::InterfaceConfiguration{controller_interface:: interface_configuration_type::NONE}; } diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index f3414584..5b43edd2 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -85,7 +85,7 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU bool torque_command_mode_ = false; double tracking_performance_; - int fri_state_; + double fri_state_; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 98891164..32793770 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -45,5 +45,10 @@ def generate_launch_description(): package="controller_manager", executable="spawner", arguments=["timing_controller", "-c", "/controller_manager"] + ), + Node( + package="controller_manager", + executable="spawner", + arguments=["robot_state_broadcaster", "-c", "/controller_manager"] ) ]) \ No newline at end of file diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index a865c1cb..326c5b3b 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -216,6 +216,9 @@ std::vector RobotControlClient::export_state RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); std::vector state_interfaces; + + state_interfaces.emplace_back( + hardware_interface::StateInterface("state", "fri_state", &fri_state_)); for (size_t i = 0; i < info_.joints.size(); i++) { state_interfaces.emplace_back( hardware_interface::StateInterface( diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index d223851f..3e8171fe 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -17,21 +17,32 @@ #include "controller_manager/controller_manager.hpp" #include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/int32.hpp" int main(int argc, char** argv) { rclcpp::init(argc, argv); + int fri_state_ = 0; auto executor = std::make_shared(); auto controller_manager = std::make_shared(executor, "controller_manager"); - std::thread control_loop([controller_manager]() { + std::thread control_loop([controller_manager, &fri_state_]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); - // TODO(Svastits): wait for FRI state changed?? + auto callback = [&fri_state_](std_msgs::msg::Int32::SharedPtr state) {fri_state_ = state->data;}; + controller_manager->create_subscription("fri_state", 1, callback); + // TODO(Svastits): sync controller start state with robot pose at startup // currently if robot is not in candle, speed limit is exceeded at startup + while (rclcpp::ok()) { + if (fri_state_ < 2) + { + // TODO(Svastits): adjust wait time + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + continue; + } controller_manager->read(controller_manager->now(), dt); // Blocking until state received controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); From 162db6e2d925513c08ebcc1956a7397001e4c287 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 12 Jul 2022 08:36:49 +0200 Subject: [PATCH 20/94] fix subscription, uncrustify --- .../kuka_sunrise/robot_manager_node.hpp | 6 +- .../src/kuka_sunrise/robot_control_client.cpp | 19 +++--- .../src/kuka_sunrise/robot_manager_node.cpp | 64 +++++++++++-------- .../src/kuka_sunrise/sunrise_control_node.cpp | 49 ++++++++------ 4 files changed, 77 insertions(+), 61 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index 22c1bdff..60bbb858 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -66,8 +66,10 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat rclcpp::Client::SharedPtr change_robot_control_state_client_; rclcpp::Client::SharedPtr set_parameter_client_; rclcpp::Client::SharedPtr set_commanding_state_client_; - rclcpp::Client::SharedPtr change_hardware_state_client_; - rclcpp::Client::SharedPtr change_controller_state_client_; + rclcpp::Client::SharedPtr + change_hardware_state_client_; + rclcpp::Client::SharedPtr + change_controller_state_client_; rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp::Service::SharedPtr change_robot_commanding_state_service_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 326c5b3b..04097c19 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -83,14 +83,13 @@ CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) { - RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activating client"); - if(!client_application_.connect(30200, nullptr)) - { - RCLCPP_ERROR(rclcpp::get_logger("HWIF"),"could not connect"); - return CallbackReturn::FAILURE; + RCLCPP_INFO(rclcpp::get_logger("HWIF"), "activating client"); + if (!client_application_.connect(30200, nullptr)) { + RCLCPP_ERROR(rclcpp::get_logger("HWIF"), "could not connect"); + return CallbackReturn::FAILURE; } activate(); - RCLCPP_INFO(rclcpp::get_logger("HWIF"),"activated client"); + RCLCPP_INFO(rclcpp::get_logger("HWIF"), "activated client"); return CallbackReturn::SUCCESS; } @@ -142,8 +141,8 @@ hardware_interface::return_type RobotControlClient::read( const rclcpp::Duration &) { if (!is_active_) { - RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Controller not active"); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); + RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Controller not active"); + std::this_thread::sleep_for(std::chrono::milliseconds(50)); return hardware_interface::return_type::ERROR; } @@ -218,7 +217,7 @@ std::vector RobotControlClient::export_state std::vector state_interfaces; state_interfaces.emplace_back( - hardware_interface::StateInterface("state", "fri_state", &fri_state_)); + hardware_interface::StateInterface("state", "fri_state", &fri_state_)); for (size_t i = 0; i < info_.joints.size(); i++) { state_interfaces.emplace_back( hardware_interface::StateInterface( @@ -242,7 +241,7 @@ std::vector RobotControlClient::export_com std::vector command_interfaces; command_interfaces.emplace_back( - hardware_interface::CommandInterface("timing","receive_multiplier", &receive_multiplier_)); + hardware_interface::CommandInterface("timing", "receive_multiplier", &receive_multiplier_)); for (size_t i = 0; i < info_.joints.size(); i++) { command_interfaces.emplace_back( hardware_interface::CommandInterface( diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index e1a7f859..1c64a679 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -37,10 +37,12 @@ RobotManagerNode::RobotManagerNode() "robot_control/change_state", qos.get_rmw_qos_profile(), cbg_); set_commanding_state_client_ = this->create_client( "robot_control/set_commanding_state", qos.get_rmw_qos_profile(), cbg_); - change_hardware_state_client_ = this->create_client( + change_hardware_state_client_ = + this->create_client( "controller_manager/set_hardware_component_state", qos.get_rmw_qos_profile(), cbg_); - change_controller_state_client_ = this->create_client( - "controller_manager/configure_and_start_controller", qos.get_rmw_qos_profile(), cbg_); + change_controller_state_client_ = + this->create_client( + "controller_manager/configure_and_start_controller", qos.get_rmw_qos_profile(), cbg_); auto command_srv_callback = [this]( std_srvs::srv::SetBool::Request::SharedPtr request, std_srvs::srv::SetBool::Response::SharedPtr response) { @@ -153,15 +155,17 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "set FRI config"); // Activate hardware interface - auto hw_request = std::make_shared(); + auto hw_request = + std::make_shared(); hw_request->name = "iiwa_hardware"; hw_request->target_state.label = "active"; - auto hw_response = kuka_sunrise::sendRequest( + auto hw_response = + kuka_sunrise::sendRequest( change_hardware_state_client_, hw_request, 0, 2000); - if (!hw_response || !hw_response->ok) { - RCLCPP_ERROR(get_logger(), "Could not activate hardware interface"); - return FAILURE; - } + if (!hw_response || !hw_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not activate hardware interface"); + return FAILURE; + } RCLCPP_ERROR(get_logger(), "activated HWIF"); @@ -174,31 +178,35 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "started FRI"); // Activate joint state broadcaster - auto controller_request = std::make_shared(); + auto controller_request = + std::make_shared(); controller_request->name = "joint_state_broadcaster"; - auto controller_response = kuka_sunrise::sendRequest( - change_controller_state_client_, controller_request, 0, 2000); - if (!controller_response || !controller_response->ok) { - RCLCPP_ERROR(get_logger(), "Could not activate broadcaster"); - return FAILURE; - } + auto controller_response = + kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not activate broadcaster"); + return FAILURE; + } - RCLCPP_ERROR(get_logger(), "activated joint state broadcaster"); + RCLCPP_ERROR(get_logger(), "activated joint state broadcaster"); - // Activate forward_command_controller - // TODO(Svastits): add parameter for controller name - controller_request->name = "forward_command_controller_position"; - controller_response = kuka_sunrise::sendRequest( - change_controller_state_client_, controller_request, 0, 2000); - if (!controller_response || !controller_response->ok) { - RCLCPP_ERROR(get_logger(), "Could not activate controller"); - return FAILURE; - } + // Activate forward_command_controller + // TODO(Svastits): add parameter for controller name + controller_request->name = "forward_command_controller_position"; + controller_response = + kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not activate controller"); + return FAILURE; + } RCLCPP_ERROR(get_logger(), "activated controller"); command_state_changed_publisher_->on_activate(); // Start commanding mode - if (!activate()) - return FAILURE; + if (!activate()) { + return FAILURE; + } return SUCCESS; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 3e8171fe..100ccd2b 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -19,38 +19,45 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/int32.hpp" -int main(int argc, char** argv) +int main(int argc, char ** argv) { rclcpp::init(argc, argv); int fri_state_ = 0; auto executor = std::make_shared(); - auto controller_manager = std::make_shared(executor, "controller_manager"); - + auto controller_manager = std::make_shared( + executor, + "controller_manager"); + auto cbg = + controller_manager->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); std::thread control_loop([controller_manager, &fri_state_]() { - const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); - - auto callback = [&fri_state_](std_msgs::msg::Int32::SharedPtr state) {fri_state_ = state->data;}; - controller_manager->create_subscription("fri_state", 1, callback); + const rclcpp::Duration dt = + rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); - // TODO(Svastits): sync controller start state with robot pose at startup - // currently if robot is not in candle, speed limit is exceeded at startup + auto callback = [&fri_state_, controller_manager](std_msgs::msg::Int32::SharedPtr state) { + RCLCPP_INFO(controller_manager->get_logger(), "State received: %i", state->data); + fri_state_ = state->data; + }; + auto sub = + controller_manager->create_subscription("fri_state", 1, callback); + RCLCPP_INFO(controller_manager->get_logger(), "REACHED"); + // TODO(Svastits): sync controller start state with robot pose at startup + // currently if robot is not in candle, speed limit is exceeded at startup - while (rclcpp::ok()) { - if (fri_state_ < 2) - { - // TODO(Svastits): adjust wait time - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - continue; + while (rclcpp::ok()) { + if (fri_state_ < 2) { + // TODO(Svastits): adjust wait time + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + continue; + } + controller_manager->read(controller_manager->now(), dt); // Blocking until state received + controller_manager->update(controller_manager->now(), dt); + controller_manager->write(controller_manager->now(), dt); } - controller_manager->read(controller_manager->now(), dt); // Blocking until state received - controller_manager->update(controller_manager->now(), dt); - controller_manager->write(controller_manager->now(), dt); - } - }); + }); executor->add_node(controller_manager); - + executor->spin(); control_loop.join(); From 5445d555c8958f7afbc69a5707b2f34938f83a9c Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 12 Jul 2022 12:21:11 +0200 Subject: [PATCH 21/94] remove fri state condition cannot start controllers in this setup --- .../include/kuka_sunrise/robot_control_client.hpp | 2 +- .../src/kuka_sunrise/sunrise_control_node.cpp | 15 +++++---------- 2 files changed, 6 insertions(+), 11 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index 5b43edd2..6426c1f0 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -85,7 +85,7 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU bool torque_command_mode_ = false; double tracking_performance_; - double fri_state_; + double fri_state_ = 0; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 100ccd2b..62278bf6 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -28,8 +28,6 @@ int main(int argc, char ** argv) auto controller_manager = std::make_shared( executor, "controller_manager"); - auto cbg = - controller_manager->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); std::thread control_loop([controller_manager, &fri_state_]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); @@ -40,19 +38,16 @@ int main(int argc, char ** argv) }; auto sub = controller_manager->create_subscription("fri_state", 1, callback); - RCLCPP_INFO(controller_manager->get_logger(), "REACHED"); // TODO(Svastits): sync controller start state with robot pose at startup // currently if robot is not in candle, speed limit is exceeded at startup - while (rclcpp::ok()) { - if (fri_state_ < 2) { - // TODO(Svastits): adjust wait time - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - continue; - } - controller_manager->read(controller_manager->now(), dt); // Blocking until state received + //if (fri_state_ > 1) { + controller_manager->read(controller_manager->now(), dt); controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); + //} + //else + std::this_thread::sleep_for(std::chrono::milliseconds(10)); // TODO(Svastits): adjust wait time } }); From 785b4a2c420dcef467f01c8ce83b437a00671620 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 12 Jul 2022 12:28:49 +0200 Subject: [PATCH 22/94] remove unnecessary include in cmakelists --- kuka_sunrise_driver/CMakeLists.txt | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 60278c6d..f4b349e1 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -31,8 +31,7 @@ find_package(pluginlib REQUIRED) find_package(controller_manager) find_package(controller_manager_msgs) -include_directories(include /home/rosdeveloper/ros2_ws/src/ros2_kuka_drivers/fri_client/include) - +include_directories(include) add_library(internal SHARED include/kuka_sunrise/internal/activatable_interface.hpp From f84fcae1d14b88ad62293bd4a1666388640ac325 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 12 Jul 2022 12:32:58 +0200 Subject: [PATCH 23/94] move ros2_control config file to kuka_sunrise package --- .../config/iiwa_ros2_controller_config.yaml | 17 +++++++++++++++++ .../launch/kuka_sunrise_control.launch.py | 2 +- 2 files changed, 18 insertions(+), 1 deletion(-) create mode 100755 kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml diff --git a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml new file mode 100755 index 00000000..d92e3f38 --- /dev/null +++ b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml @@ -0,0 +1,17 @@ +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + forward_command_controller_position: + type: forward_command_controller/ForwardCommandController + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + timing_controller: + type: kuka_controllers/TimingController + + robot_state_broadcaster: + type: kuka_controllers/RobotStateBroadcaster + + configure_components_on_start: ["iiwa_hardware"] diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 32793770..bf758f2f 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -15,7 +15,7 @@ def load_file(absolute_file_path): def generate_launch_description(): - controller_config = get_package_share_directory('urdflbriiwa7') + "/config/iiwa_ros2_controller_config.yaml" + controller_config = get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml" forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") robot_description = {'robot_description' : robot_description_config} From 93ab5dca6f04ec353494dbead02398fb7bec9120 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 12 Jul 2022 15:42:33 +0200 Subject: [PATCH 24/94] adjust to renamed iiwa7 package --- kuka_sunrise_driver/launch/basic_launch.py | 6 +++--- kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index 3a3ac43a..9c0ffd7f 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -14,13 +14,13 @@ def load_file(absolute_file_path): def generate_launch_description(): - controller_config = get_package_share_directory('urdflbriiwa7') + "/config/iiwa_ros2_controller_config.yaml" + controller_config = get_package_share_directory('kuka_lbr_iiwa7_support') + "/config/iiwa_ros2_controller_config.yaml" forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" - robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") + robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/urdflbriiwa7.urdf") robot_description = {'robot_description' : robot_description_config} rviz_config_file = os.path.join( - get_package_share_directory('urdflbriiwa7'), 'launch', 'urdf.rviz') + get_package_share_directory('kuka_lbr_iiwa7_support'), 'launch', 'urdf.rviz') return LaunchDescription([ Node( diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index bf758f2f..c3bf59cf 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -17,7 +17,7 @@ def load_file(absolute_file_path): def generate_launch_description(): controller_config = get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml" forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" - robot_description_config = load_file(get_package_share_directory('urdflbriiwa7') + "/urdf/urdflbriiwa7.urdf") + robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/urdflbriiwa7.urdf") robot_description = {'robot_description' : robot_description_config} return LaunchDescription([ From 1c0b9d67d8fe491f2edfaf71088e059bd4a48e28 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 11:28:32 +0200 Subject: [PATCH 25/94] remove thread sleep --- kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 62278bf6..31b6e955 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -41,13 +41,9 @@ int main(int argc, char ** argv) // TODO(Svastits): sync controller start state with robot pose at startup // currently if robot is not in candle, speed limit is exceeded at startup while (rclcpp::ok()) { - //if (fri_state_ > 1) { controller_manager->read(controller_manager->now(), dt); controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); - //} - //else - std::this_thread::sleep_for(std::chrono::milliseconds(10)); // TODO(Svastits): adjust wait time } }); From 8600690be2089c38644231d571b2c3757019f6f6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 15:31:03 +0200 Subject: [PATCH 26/94] naming convention, log message fixes --- .../src/kuka_sunrise/robot_manager_node.cpp | 30 ++++++++----------- .../src/kuka_sunrise/sunrise_control_node.cpp | 10 +++---- 2 files changed, 16 insertions(+), 24 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 1c64a679..03bf300f 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -143,17 +143,14 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "not connected"); return ERROR; } - RCLCPP_ERROR(get_logger(), "activating"); - auto send_period_ms = static_cast(this->get_parameter("send_period_ms").as_int()); auto receive_multiplier = static_cast(this->get_parameter("receive_multiplier").as_int()); - if (!robot_manager_->setFRIConfig(30200, send_period_ms, receive_multiplier)) { RCLCPP_ERROR(get_logger(), "could not set fri config"); return FAILURE; } - RCLCPP_ERROR(get_logger(), "set FRI config"); + RCLCPP_INFO(get_logger(), "set FRI config"); // Activate hardware interface auto hw_request = std::make_shared(); @@ -167,15 +164,15 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } - RCLCPP_ERROR(get_logger(), "activated HWIF"); + RCLCPP_INFO(get_logger(), "Activated LBR iiwa hardware interface"); // Start FRI (in monitoring mode) if (!robot_manager_->startFRI()) { - RCLCPP_ERROR(get_logger(), "could not start fri"); + RCLCPP_ERROR(get_logger(), "Could not start FRI"); return FAILURE; } - RCLCPP_ERROR(get_logger(), "started FRI"); + RCLCPP_INFO(get_logger(), "Started FRI"); // Activate joint state broadcaster auto controller_request = @@ -189,8 +186,6 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } - RCLCPP_ERROR(get_logger(), "activated joint state broadcaster"); - // Activate forward_command_controller // TODO(Svastits): add parameter for controller name controller_request->name = "forward_command_controller_position"; @@ -201,7 +196,6 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "Could not activate controller"); return FAILURE; } - RCLCPP_ERROR(get_logger(), "activated controller"); command_state_changed_publisher_->on_activate(); // Start commanding mode if (!activate()) { @@ -215,17 +209,17 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) { if (!robot_manager_->isConnected()) { - RCLCPP_ERROR(get_logger(), "not connected"); + RCLCPP_ERROR(get_logger(), "Not connected"); return ERROR; } if (this->isActive() && !this->deactivate()) { - RCLCPP_ERROR(get_logger(), "could not deactivate control"); + RCLCPP_ERROR(get_logger(), "Could not deactivate control"); return ERROR; } if (!robot_manager_->endFRI()) { - RCLCPP_ERROR(get_logger(), "could not end fri"); + RCLCPP_ERROR(get_logger(), "Could not end FRI"); return ERROR; } @@ -233,7 +227,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) { // TODO(resizoltan) out of sync - RCLCPP_ERROR(get_logger(), "could not deactivate"); + RCLCPP_ERROR(get_logger(), "Could not deactivate"); return ERROR; } @@ -246,14 +240,14 @@ bool RobotManagerNode::activate() { this->ActivatableInterface::activate(); if (!robot_manager_->isConnected()) { - RCLCPP_ERROR(get_logger(), "not connected"); + RCLCPP_ERROR(get_logger(), "Not connected"); return false; } if (!robot_manager_->activateControl()) { // TODO(resizoltan) check robot control node state first this->ActivatableInterface::deactivate(); - RCLCPP_ERROR(get_logger(), "could not activate control"); + RCLCPP_ERROR(get_logger(), "Could not activate control"); return false; } std_msgs::msg::Bool command_state; @@ -265,12 +259,12 @@ bool RobotManagerNode::activate() bool RobotManagerNode::deactivate() { if (!robot_manager_->isConnected()) { - RCLCPP_ERROR(get_logger(), "not connected"); + RCLCPP_ERROR(get_logger(), "Not connected"); return false; } if (this->isActive() && !robot_manager_->deactivateControl()) { - RCLCPP_ERROR(get_logger(), "could not deactivate control"); + RCLCPP_ERROR(get_logger(), "Could not deactivate control"); return false; } this->ActivatableInterface::deactivate(); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 31b6e955..95190b0d 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -23,23 +23,21 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); - int fri_state_ = 0; + int fri_state = 0; auto executor = std::make_shared(); auto controller_manager = std::make_shared( executor, "controller_manager"); - std::thread control_loop([controller_manager, &fri_state_]() { + std::thread control_loop([controller_manager, &fri_state]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); - auto callback = [&fri_state_, controller_manager](std_msgs::msg::Int32::SharedPtr state) { + auto callback = [&fri_state, controller_manager](std_msgs::msg::Int32::SharedPtr state) { RCLCPP_INFO(controller_manager->get_logger(), "State received: %i", state->data); - fri_state_ = state->data; + fri_state = state->data; }; auto sub = controller_manager->create_subscription("fri_state", 1, callback); - // TODO(Svastits): sync controller start state with robot pose at startup - // currently if robot is not in candle, speed limit is exceeded at startup while (rclcpp::ok()) { controller_manager->read(controller_manager->now(), dt); controller_manager->update(controller_manager->now(), dt); From 22c24498a708d1c72df753792f42075a05ff75d4 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 15:35:27 +0200 Subject: [PATCH 27/94] add connection quality state interface, remove unnecessary functions --- .../robot_state_broadcaster.hpp | 2 + .../src/robot_state_broadcaster.cpp | 11 ++++ .../kuka_sunrise/configuration_manager.hpp | 3 - .../kuka_sunrise/robot_control_client.hpp | 3 +- .../kuka_sunrise/configuration_manager.cpp | 57 +------------------ .../src/kuka_sunrise/robot_control_client.cpp | 28 +++------ 6 files changed, 24 insertions(+), 80 deletions(-) diff --git a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp index bb5acdbe..396749da 100644 --- a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp +++ b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp @@ -53,8 +53,10 @@ class RobotStateBroadcaster : public controller_interface::ControllerInterface private: int fri_state_ = 0; + int connection_quality_ = 0; bool resend_state_ = true; rclcpp::Publisher::SharedPtr fri_state_publisher_; + rclcpp::Publisher::SharedPtr connection_quality_publisher_; std_msgs::msg::Int32 state_msg_; }; } // namespace kuka_controllers diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp index 78819f91..a0522338 100644 --- a/kuka_controllers/src/robot_state_broadcaster.cpp +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -21,6 +21,8 @@ controller_interface::CallbackReturn RobotStateBroadcaster::on_init() // TODO(Svastits): choose appropriate QoS settings for late joiners fri_state_publisher_ = get_node()->create_publisher( "fri_state", rclcpp::SystemDefaultsQoS()); + connection_quality_publisher_ = get_node()->create_publisher( + "connection_quality", rclcpp::SystemDefaultsQoS()); return controller_interface::CallbackReturn::SUCCESS; } @@ -37,6 +39,7 @@ const controller_interface::InterfaceConfiguration config; config.type = controller_interface::interface_configuration_type::INDIVIDUAL; config.names.push_back("state/fri_state"); + config.names.push_back("state/connection_quality"); return config; } @@ -62,11 +65,19 @@ controller_interface::return_type RobotStateBroadcaster::update( const rclcpp::Time &, const rclcpp::Duration &) { + // TODO(Svastits): create custom state msg type and publish all robot state info + // with given frequency -> measure additional system overload state_msg_.data = state_interfaces_[0].get_value(); if (fri_state_ != state_msg_.data) { fri_state_ = state_msg_.data; fri_state_publisher_->publish(state_msg_); } + + state_msg_.data = state_interfaces_[1].get_value(); + if (connection_quality_ != state_msg_.data) { + connection_quality_ = state_msg_.data; + connection_quality_publisher_->publish(state_msg_); + } return controller_interface::return_type::OK; } diff --git a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp index 9e14b5aa..aa592de1 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp @@ -49,8 +49,6 @@ class ConfigurationManager rclcpp::CallbackGroup::SharedPtr param_cbg_; rclcpp::Client::SharedPtr command_mode_client_; rclcpp::Client::SharedPtr receive_multiplier_client_; - rclcpp::Client::SharedPtr sync_receive_multiplier_client_; - rclcpp::Client::SharedPtr sync_send_period_client_; rclcpp::Service::SharedPtr set_parameter_service_; std::vector joint_stiffness_ = std::vector(7, 1000.0); @@ -65,7 +63,6 @@ class ConfigurationManager bool onControllerIpChangeRequest(const std::string & controller_ip) const; bool setCommandMode(const std::string & control_mode) const; bool setReceiveMultiplier(int receive_multiplier) const; - bool setSendPeriod(int send_period) const; void setParameters(std_srvs::srv::Trigger::Response::SharedPtr response); }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp index 6426c1f0..f773b7e7 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp @@ -43,8 +43,6 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU RobotControlClient() : client_application_(udp_connection_, *this) {} ~RobotControlClient(); - bool activate(); - bool deactivate(); bool setReceiveMultiplier(int receive_multiplier); virtual void waitForCommand(); @@ -86,6 +84,7 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU bool torque_command_mode_ = false; double tracking_performance_; double fri_state_ = 0; + double connection_quality_ = 0; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 6a73084f..64aef2f6 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -39,14 +39,6 @@ ConfigurationManager::ConfigurationManager( kuka_sunrise_interfaces::srv::SetInt>( "set_receive_multiplier", qos.get_rmw_qos_profile(), cbg_); - sync_receive_multiplier_client_ = robot_manager_node->create_client< - kuka_sunrise_interfaces::srv::SetInt>( - "sync_receive_multiplier", qos.get_rmw_qos_profile(), - cbg_); - sync_send_period_client_ = robot_manager_node->create_client< - kuka_sunrise_interfaces::srv::SetInt>( - "sync_send_period", qos.get_rmw_qos_profile(), - cbg_); robot_manager_node_->registerParameter( "controller_ip", "", kroshu_ros2_core::ParameterSetAccessRights {false, false, @@ -64,7 +56,6 @@ ConfigurationManager::ConfigurationManager( bool ConfigurationManager::onCommandModeChangeRequest(const std::string & command_mode) const { - return true; if (command_mode == "position") { if (!setCommandMode("position")) { return false; @@ -96,7 +87,6 @@ bool ConfigurationManager::onCommandModeChangeRequest(const std::string & comman bool ConfigurationManager::onControlModeChangeRequest(const std::string & control_mode) const { - return true; if (control_mode == "position") { return robot_manager_->setPositionControlMode(); } else if (control_mode == "joint_impedance") { @@ -118,7 +108,6 @@ bool ConfigurationManager::onControlModeChangeRequest(const std::string & contro bool ConfigurationManager::onJointStiffnessChangeRequest( const std::vector & joint_stiffness) { - return true; if (joint_stiffness.size() != 7) { RCLCPP_ERROR( robot_manager_node_->get_logger(), @@ -138,7 +127,6 @@ bool ConfigurationManager::onJointStiffnessChangeRequest( bool ConfigurationManager::onJointDampingChangeRequest(const std::vector & joint_damping) { - return true; if (joint_damping.size() != 7) { RCLCPP_ERROR( robot_manager_node_->get_logger(), @@ -157,22 +145,17 @@ bool ConfigurationManager::onJointDampingChangeRequest(const std::vector bool ConfigurationManager::onSendPeriodChangeRequest(const int & send_period) const { - return true; if (send_period < 1 || send_period > 100) { RCLCPP_ERROR( robot_manager_node_->get_logger(), "Send period milliseconds must be >=1 && <=100"); return false; } - if (!setSendPeriod(send_period)) { - return false; - } return true; } bool ConfigurationManager::onReceiveMultiplierChangeRequest(const int & receive_multiplier) const { - return true; if (receive_multiplier < 1) { RCLCPP_ERROR(robot_manager_node_->get_logger(), "Receive multiplier must be >=1"); return false; @@ -216,25 +199,17 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr bool ConfigurationManager::setCommandMode(const std::string & control_mode) const { - auto request = std::make_shared(); + + //TODO(Svastits): load and switch controllers through controller_manager ClientCommandModeID client_command_mode; if (control_mode == "position") { - request->data = false; client_command_mode = POSITION_COMMAND_MODE; } else if (control_mode == "torque") { - request->data = true; client_command_mode = TORQUE_COMMAND_MODE; } else { RCLCPP_ERROR(robot_manager_node_->get_logger(), "Invalid control mode"); return false; } - auto response = kuka_sunrise::sendRequest( - command_mode_client_, request, 0, 1000); - - if (!response || !response->success) { - RCLCPP_ERROR(robot_manager_node_->get_logger(), "Could not set command mode"); - return false; - } if (robot_manager_) { robot_manager_->setClientCommandMode(client_command_mode); } else { @@ -256,34 +231,6 @@ bool ConfigurationManager::setReceiveMultiplier(int receive_multiplier) const RCLCPP_ERROR(robot_manager_node_->get_logger(), "Could not set receive_multiplier"); return false; } - - // TODO(Svastits): if monitoring mode is intended, no joint_controller is necessary - // syncing these parameters should be optional (applies also for send_period) - - // Sync with joint controller - response = kuka_sunrise::sendRequest( - sync_receive_multiplier_client_, request, 0, 1000); - - if (!response || !response->success) { - RCLCPP_ERROR(robot_manager_node_->get_logger(), "Could not sync receive_multiplier"); - return false; - } - return true; -} - -bool ConfigurationManager::setSendPeriod(int send_period) const -{ - // Sync with joint controller - auto request = std::make_shared(); - request->data = send_period; - - auto response = kuka_sunrise::sendRequest( - sync_send_period_client_, request, 0, 1000); - - if (!response || !response->success) { - RCLCPP_ERROR(robot_manager_node_->get_logger(), "Could not sync send_period"); - return false; - } return true; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp index 04097c19..4ac29807 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp @@ -20,8 +20,6 @@ namespace kuka_sunrise { CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInfo & system_info) { -// TODO(Svastits): add parameter for command mode, receive multiplier etc - if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; } @@ -88,7 +86,7 @@ CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(rclcpp::get_logger("HWIF"), "could not connect"); return CallbackReturn::FAILURE; } - activate(); + this->ActivatableInterface::activate(); RCLCPP_INFO(rclcpp::get_logger("HWIF"), "activated client"); return CallbackReturn::SUCCESS; } @@ -96,7 +94,7 @@ CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) CallbackReturn RobotControlClient::on_deactivate(const rclcpp_lifecycle::State &) { client_application_.disconnect(); - deactivate(); + this->ActivatableInterface::deactivate(); return CallbackReturn::SUCCESS; } @@ -104,18 +102,6 @@ RobotControlClient::~RobotControlClient() { } -bool RobotControlClient::activate() -{ - this->ActivatableInterface::activate(); - return true; // TODO(resizoltan) check if successful -} - -bool RobotControlClient::deactivate() -{ - this->ActivatableInterface::deactivate(); - return true; // TODO(resizoltan) check if successful -} - void RobotControlClient::waitForCommand() { // TODO(Svastits): is this really the purpose of waitForCommand? @@ -159,7 +145,7 @@ hardware_interface::return_type RobotControlClient::read( tracking_performance_ = robotState().getTrackingPerformance(); fri_state_ = robotState().getSessionState(); - // RCLCPP_INFO(rclcpp::get_logger("ClientApplication"), "FRI state: %i", fri_state_); + connection_quality_ = robotState().getConnectionQuality(); // const double* external_torque = robotState().getExternalTorque(); // hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); @@ -191,7 +177,7 @@ void RobotControlClient::updateCommand(const rclcpp::Time &) printf("client deactivated, exiting updateCommand\n"); return; } - + // TODO(Svastits): implement command mode switch if (torque_command_mode_) { const double * joint_torques_ = hw_effort_command_.data(); robotCommand().setJointPosition(robotState().getIpoJointPosition()); @@ -210,14 +196,16 @@ void RobotControlClient::updateCommand(const rclcpp::Time &) std::vector RobotControlClient::export_state_interfaces() { - - // TODO(Svastits): add FRI state interface RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); std::vector state_interfaces; state_interfaces.emplace_back( hardware_interface::StateInterface("state", "fri_state", &fri_state_)); + + state_interfaces.emplace_back( + hardware_interface::StateInterface("state", "connection_quality", &connection_quality_)); + for (size_t i = 0; i < info_.joints.size(); i++) { state_interfaces.emplace_back( hardware_interface::StateInterface( From 820ac818ccc046d2e1f92615cb6597078021e44a Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 15:35:57 +0200 Subject: [PATCH 28/94] Set receive multiplier of hardware interface --- kuka_controllers/CMakeLists.txt | 3 ++- .../include/kuka_controllers/timing_controller.hpp | 3 ++- kuka_controllers/package.xml | 1 + kuka_controllers/src/timing_controller.cpp | 11 +++++++++++ .../src/kuka_sunrise/configuration_manager.cpp | 2 +- 5 files changed, 17 insertions(+), 3 deletions(-) diff --git a/kuka_controllers/CMakeLists.txt b/kuka_controllers/CMakeLists.txt index 81c2cc1a..96173d43 100644 --- a/kuka_controllers/CMakeLists.txt +++ b/kuka_controllers/CMakeLists.txt @@ -10,6 +10,7 @@ find_package(controller_interface REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) +find_package(kuka_sunrise_interfaces REQUIRED) include_directories(include) @@ -21,7 +22,7 @@ target_include_directories(${PROJECT_NAME} PRIVATE include ) -ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface std_msgs +ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface std_msgs kuka_sunrise_interfaces ) pluginlib_export_plugin_description_file(controller_interface controller_plugins.xml) diff --git a/kuka_controllers/include/kuka_controllers/timing_controller.hpp b/kuka_controllers/include/kuka_controllers/timing_controller.hpp index 2e161eea..75b4b62b 100644 --- a/kuka_controllers/include/kuka_controllers/timing_controller.hpp +++ b/kuka_controllers/include/kuka_controllers/timing_controller.hpp @@ -24,7 +24,7 @@ #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp/time.hpp" #include "rclcpp/duration.hpp" - +#include "kuka_sunrise_interfaces/srv/set_int.hpp" namespace kuka_controllers { @@ -51,6 +51,7 @@ class TimingController : public controller_interface::ControllerInterface controller_interface::CallbackReturn on_init() override; private: + rclcpp::Service::SharedPtr receive_multiplier_service_; int receive_multiplier_ = 1; bool resend_multiplier_ = true; }; diff --git a/kuka_controllers/package.xml b/kuka_controllers/package.xml index c060961a..658fdbde 100644 --- a/kuka_controllers/package.xml +++ b/kuka_controllers/package.xml @@ -15,6 +15,7 @@ pluginlib rclcpp_lifecycle std_msgs + kuka_sunrise_interfaces ament_cmake diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp index 858b40d1..f38fc22f 100644 --- a/kuka_controllers/src/timing_controller.cpp +++ b/kuka_controllers/src/timing_controller.cpp @@ -18,6 +18,14 @@ namespace kuka_controllers { controller_interface::CallbackReturn TimingController::on_init() { + auto callback = [this](kuka_sunrise_interfaces::srv::SetInt::Request::SharedPtr request, + kuka_sunrise_interfaces::srv::SetInt::Response::SharedPtr response) { + resend_multiplier_ = true; + receive_multiplier_ = request->data; + response->success = true; + }; + receive_multiplier_service_ = get_node()->create_service( + "set_receive_multiplier", callback); // TODO(Svastits): create service to get multiplier changes (or perpaps parameter??) // and set resend_multiplier_ to true in the callback return controller_interface::CallbackReturn::SUCCESS; @@ -62,6 +70,9 @@ controller_interface::return_type TimingController::update( { // TODO(Svastits): disable changes if HWIF is active if (resend_multiplier_) { + RCLCPP_INFO( + get_node()->get_logger(), "Changing receive multiplier of hardware interface to %i", + receive_multiplier_); command_interfaces_[0].set_value(receive_multiplier_); resend_multiplier_ = false; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 64aef2f6..b6bb03f6 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -221,7 +221,7 @@ bool ConfigurationManager::setCommandMode(const std::string & control_mode) cons bool ConfigurationManager::setReceiveMultiplier(int receive_multiplier) const { - // Set parameter of control client + // Set receive multiplier of hardware interface through controller manager service auto request = std::make_shared(); request->data = receive_multiplier; auto response = kuka_sunrise::sendRequest( From 6888a63ebf407d99baffae2c8f229ecb501ca044 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 15:58:04 +0200 Subject: [PATCH 29/94] rename HWIF and remove unused code --- kuka_sunrise_driver/CMakeLists.txt | 14 +- kuka_sunrise_driver/hardware_interface.xml | 2 +- ...nt.hpp => kuka_fri_hardware_interface.hpp} | 8 +- .../include/kuka_sunrise/robot_commander.hpp | 129 ------------- .../kuka_sunrise/robot_control_node.hpp | 71 -------- .../include/kuka_sunrise/robot_observer.hpp | 101 ----------- ...nt.cpp => kuka_fri_hardware_interface.cpp} | 28 +-- .../src/kuka_sunrise/robot_commander.cpp | 152 ---------------- .../src/kuka_sunrise/robot_control_node.cpp | 169 ------------------ .../src/kuka_sunrise/robot_observer.cpp | 147 --------------- 10 files changed, 22 insertions(+), 799 deletions(-) rename kuka_sunrise_driver/include/kuka_sunrise/{robot_control_client.hpp => kuka_fri_hardware_interface.hpp} (93%) delete mode 100644 kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp delete mode 100644 kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp delete mode 100644 kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp rename kuka_sunrise_driver/src/kuka_sunrise/{robot_control_client.cpp => kuka_fri_hardware_interface.cpp} (88%) delete mode 100644 kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp delete mode 100644 kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp delete mode 100644 kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index f4b349e1..c292a52c 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -49,9 +49,8 @@ add_library(robot_manager SHARED src/kuka_sunrise/tcp_connection.cpp) add_library(robot_control_client SHARED - src/kuka_sunrise/robot_control_client.cpp - src/kuka_sunrise/robot_observer.cpp - src/kuka_sunrise/robot_commander.cpp) + src/kuka_sunrise/kuka_fri_hardware_interface.cpp +) ament_target_dependencies(robot_control_client kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs sensor_msgs std_srvs hardware_interface) target_link_libraries(robot_control_client fri::fri_client) @@ -67,13 +66,6 @@ target_link_libraries(robot_manager_node robot_manager configuration_manager) -add_executable(robot_control_node - src/kuka_sunrise/robot_control_node.cpp) -ament_target_dependencies(robot_control_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs sensor_msgs std_srvs kroshu_ros2_core) -target_link_libraries(robot_control_node - robot_control_client fri::fri_client) - - add_executable(sunrise_control_node src/kuka_sunrise/sunrise_control_node.cpp) ament_target_dependencies(sunrise_control_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle controller_manager) @@ -92,7 +84,7 @@ ament_target_dependencies(lifecycle_client_node rclcpp rclcpp_lifecycle std_msgs pluginlib_export_plugin_description_file(hardware_interface hardware_interface.xml) -install(TARGETS robot_manager robot_control_client robot_manager_node robot_control_node position_controller_node torque_controller_node lifecycle_client_node sunrise_control_node +install(TARGETS robot_manager robot_control_client robot_manager_node position_controller_node torque_controller_node lifecycle_client_node sunrise_control_node DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch diff --git a/kuka_sunrise_driver/hardware_interface.xml b/kuka_sunrise_driver/hardware_interface.xml index fdaee7f2..571e99f6 100644 --- a/kuka_sunrise_driver/hardware_interface.xml +++ b/kuka_sunrise_driver/hardware_interface.xml @@ -1,6 +1,6 @@ - ROS2 control hardware interface for KUKA LBR robots using the Fast Robot Interface (FRI). diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp similarity index 93% rename from kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp rename to kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index f773b7e7..bdcef4e6 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_client.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -36,13 +36,13 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface namespace kuka_sunrise { -class RobotControlClient : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, +class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, public ActivatableInterface { public: - RobotControlClient() + KUKAFRIHardwareInterface() : client_application_(udp_connection_, *this) {} - ~RobotControlClient(); + ~KUKAFRIHardwareInterface(); bool setReceiveMultiplier(int receive_multiplier); virtual void waitForCommand(); @@ -82,7 +82,7 @@ class RobotControlClient : public hardware_interface::SystemInterface, public KU KUKA::FRI::UdpConnection udp_connection_; bool torque_command_mode_ = false; - double tracking_performance_; + double tracking_performance_ = 1; double fri_state_ = 0; double connection_quality_ = 0; }; diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp deleted file mode 100644 index 70f97079..00000000 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_commander.hpp +++ /dev/null @@ -1,129 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef KUKA_SUNRISE__ROBOT_COMMANDER_HPP_ -#define KUKA_SUNRISE__ROBOT_COMMANDER_HPP_ - -#include -#include -#include -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "std_srvs/srv/set_bool.hpp" -#include "rclcpp/message_memory_strategy.hpp" -#include "rclcpp/strategies/message_pool_memory_strategy.hpp" -#include "rclcpp/strategies/allocator_memory_strategy.hpp" - -#include "kuka_sunrise/internal/activatable_interface.hpp" -#include "fri/friLBRClient.h" - -namespace kuka_sunrise -{ - -using rclcpp::message_memory_strategy::MessageMemoryStrategy; -using rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy; -using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy; - -class OutputSubscriptionBase -{ -public: - virtual void updateOutput() = 0; - virtual ~OutputSubscriptionBase() - { - } -}; - -template -class OutputSubscription : public OutputSubscriptionBase -{ -public: - OutputSubscription( - std::string name, std::function output_setter_func, - const bool & is_commanding_active_flag, - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node) - : name_(name), setOutput_(output_setter_func), is_commanding_active_(is_commanding_active_flag) - { - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - auto msg_strategy = std::make_shared>(); - subscription_ = robot_control_node->create_subscription( - name_, qos, [this](typename ROSType::ConstSharedPtr msg) - {this->commandReceivedCallback(msg);}, - rclcpp::SubscriptionOptions(), msg_strategy); - } - - virtual void updateOutput() - { - std::lock_guard lk(m_); - setOutput_(name_, output_msg_->data); - } - -private: - std::string name_; - std::function setOutput_; - const bool & is_commanding_active_; - typename ROSType::ConstSharedPtr output_msg_; - typename rclcpp::Subscription::SharedPtr subscription_; - - std::mutex m_; - - void commandReceivedCallback(typename ROSType::ConstSharedPtr msg) - { - std::lock_guard lk(m_); - if (is_commanding_active_) { - output_msg_ = msg; - } - } -}; - -class RobotCommander : public ActivatableInterface -{ -public: - RobotCommander( - KUKA::FRI::LBRCommand & robot_command, const KUKA::FRI::LBRState & robot_state_); - void addBooleanOutputCommander(const std::string & name); - void addDigitalOutputCommander(const std::string & name); - void addAnalogOutputCommander(const std::string & name); - bool setTorqueCommanding(bool is_torque_mode_active); - void updateCommand(const rclcpp::Time & stamp); - void isCommandReady(); - const KUKA::FRI::LBRCommand & getCommand(); - bool deactivate(); - -private: - KUKA::FRI::LBRCommand & robot_command_; - const KUKA::FRI::LBRState & robot_state_; - bool torque_command_mode_; // TODO(resizoltan) use atomic instead? - sensor_msgs::msg::JointState::ConstSharedPtr joint_command_msg_; - - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; - rclcpp::Subscription::SharedPtr joint_command_subscription_; - std::list> output_subscriptions_; - rclcpp::Service::SharedPtr set_command_mode_service_; - - rclcpp::Clock ros_clock_; - void commandReceivedCallback(sensor_msgs::msg::JointState::ConstSharedPtr msg); - - std::mutex m_; - std::condition_variable cv_; -}; - -} // namespace kuka_sunrise - -#endif // KUKA_SUNRISE__ROBOT_COMMANDER_HPP_ diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp deleted file mode 100644 index 79bc3756..00000000 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_control_node.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef KUKA_SUNRISE__ROBOT_CONTROL_NODE_HPP_ -#define KUKA_SUNRISE__ROBOT_CONTROL_NODE_HPP_ - -#include -#include -#include -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "std_srvs/srv/set_bool.hpp" - -#include "fri/HWIFClientApplication.hpp" -#include "fri/friUdpConnection.h" -#include "kuka_sunrise/robot_control_client.hpp" -#include "kuka_sunrise/internal/activatable_interface.hpp" -#include "kuka_sunrise_interfaces/srv/get_state.hpp" - -#include "kroshu_ros2_core/ROS2BaseLCNode.hpp" - -namespace kuka_sunrise -{ - -class RobotControlNode : public kroshu_ros2_core::ROS2BaseLCNode, public ActivatableInterface -{ -public: - RobotControlNode(); - void runClientApplication(); - - virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_configure(const rclcpp_lifecycle::State &); - - virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_cleanup(const rclcpp_lifecycle::State &); - - virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_activate(const rclcpp_lifecycle::State &); - - virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_deactivate(const rclcpp_lifecycle::State &); - - virtual bool activate(); - virtual bool deactivate(); - -private: - KUKA::FRI::UdpConnection udp_connection_; - std::unique_ptr client_; - - std::unique_ptr client_application_thread_; - std::atomic_bool close_requested_; - rclcpp::CallbackGroup::SharedPtr cbg_; - rclcpp::Service::SharedPtr set_commanding_state_service_; - rclcpp::Service::SharedPtr get_fri_state_service_; -}; - -} // namespace kuka_sunrise -#endif // KUKA_SUNRISE__ROBOT_CONTROL_NODE_HPP_ diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp deleted file mode 100644 index 12c25895..00000000 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_observer.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef KUKA_SUNRISE__ROBOT_OBSERVER_HPP_ -#define KUKA_SUNRISE__ROBOT_OBSERVER_HPP_ - -#include -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node_impl.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "std_msgs/msg/u_int64.hpp" -#include "std_msgs/msg/float64.hpp" - -#include "kuka_sunrise/internal/activatable_interface.hpp" -#include "fri/friLBRClient.h" - -namespace kuka_sunrise -{ - -// TODO(resizoltan): use message types with headers instead? -class InputPublisherBase -{ -public: - virtual void publishInputValue() = 0; - virtual ~InputPublisherBase() - { - } -}; - -template -class InputPublisher : public InputPublisherBase, public ActivatableInterface -{ -public: - InputPublisher( - std::string name, std::function input_getter_func, - rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node) - : name_(name), getInput_(input_getter_func) - { - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - publisher_ = robot_control_node->create_publisher(name_, qos); - } - virtual void publishInputValue() - { - ROSType msg; - msg.data = getInput_(name_); - publisher_->publish(msg); - } - -private: - std::string name_; - std::function getInput_; - typename rclcpp::Publisher::SharedPtr publisher_; -}; - -class RobotObserver : public ActivatableInterface -{ -public: - RobotObserver( - const KUKA::FRI::LBRState & robot_state); - void addBooleanInputObserver(std::string name); - void addDigitalInputObserver(std::string name); - void addAnalogInputObserver(std::string name); - void publishRobotState(const rclcpp::Time & stamp); - virtual bool activate(); - virtual bool deactivate(); - -private: - const KUKA::FRI::LBRState & robot_state_; - sensor_msgs::msg::JointState joint_state_msg_; - - // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - joint_state_publisher_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - joint_state_publisher2_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - tracking_performance_publisher_; - std::list> input_publishers_; - - int i = 0; -}; - -} // namespace kuka_sunrise - -#endif // KUKA_SUNRISE__ROBOT_OBSERVER_HPP_ diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp similarity index 88% rename from kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp rename to kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 4ac29807..992abf1f 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_client.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -14,11 +14,11 @@ #include -#include "kuka_sunrise/robot_control_client.hpp" +#include "kuka_sunrise/kuka_fri_hardware_interface.hpp" namespace kuka_sunrise { -CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInfo & system_info) +CallbackReturn KUKAFRIHardwareInterface::on_init(const hardware_interface::HardwareInfo & system_info) { if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; @@ -74,12 +74,12 @@ CallbackReturn RobotControlClient::on_init(const hardware_interface::HardwareInf return CallbackReturn::SUCCESS; } -CallbackReturn RobotControlClient::on_configure(const rclcpp_lifecycle::State &) +CallbackReturn KUKAFRIHardwareInterface::on_configure(const rclcpp_lifecycle::State &) { return CallbackReturn::SUCCESS; } -CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) +CallbackReturn KUKAFRIHardwareInterface::on_activate(const rclcpp_lifecycle::State &) { RCLCPP_INFO(rclcpp::get_logger("HWIF"), "activating client"); if (!client_application_.connect(30200, nullptr)) { @@ -91,18 +91,18 @@ CallbackReturn RobotControlClient::on_activate(const rclcpp_lifecycle::State &) return CallbackReturn::SUCCESS; } -CallbackReturn RobotControlClient::on_deactivate(const rclcpp_lifecycle::State &) +CallbackReturn KUKAFRIHardwareInterface::on_deactivate(const rclcpp_lifecycle::State &) { client_application_.disconnect(); this->ActivatableInterface::deactivate(); return CallbackReturn::SUCCESS; } -RobotControlClient::~RobotControlClient() +KUKAFRIHardwareInterface::~KUKAFRIHardwareInterface() { } -void RobotControlClient::waitForCommand() +void KUKAFRIHardwareInterface::waitForCommand() { // TODO(Svastits): is this really the purpose of waitForCommand? rclcpp::Time stamp = ros_clock_.now(); @@ -112,7 +112,7 @@ void RobotControlClient::waitForCommand() } } -void RobotControlClient::command() +void KUKAFRIHardwareInterface::command() { rclcpp::Time stamp = ros_clock_.now(); if (++receive_counter_ == receive_multiplier_) { @@ -122,7 +122,7 @@ void RobotControlClient::command() } -hardware_interface::return_type RobotControlClient::read( +hardware_interface::return_type KUKAFRIHardwareInterface::read( const rclcpp::Time &, const rclcpp::Duration &) { @@ -153,7 +153,7 @@ hardware_interface::return_type RobotControlClient::read( return hardware_interface::return_type::OK; } -hardware_interface::return_type RobotControlClient::write( +hardware_interface::return_type KUKAFRIHardwareInterface::write( const rclcpp::Time &, const rclcpp::Duration &) { @@ -171,7 +171,7 @@ hardware_interface::return_type RobotControlClient::write( return hardware_interface::return_type::OK; } -void RobotControlClient::updateCommand(const rclcpp::Time &) +void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) { if (!is_active_) { printf("client deactivated, exiting updateCommand\n"); @@ -194,7 +194,7 @@ void RobotControlClient::updateCommand(const rclcpp::Time &) */ } -std::vector RobotControlClient::export_state_interfaces() +std::vector KUKAFRIHardwareInterface::export_state_interfaces() { RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); @@ -222,7 +222,7 @@ std::vector RobotControlClient::export_state return state_interfaces; } -std::vector RobotControlClient::export_command_interfaces() +std::vector KUKAFRIHardwareInterface::export_command_interfaces() { RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_command_interfaces()"); @@ -251,6 +251,6 @@ std::vector RobotControlClient::export_com PLUGINLIB_EXPORT_CLASS( - kuka_sunrise::RobotControlClient, + kuka_sunrise::KUKAFRIHardwareInterface, hardware_interface::SystemInterface ) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp deleted file mode 100644 index afe32763..00000000 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_commander.cpp +++ /dev/null @@ -1,152 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include "kuka_sunrise/robot_commander.hpp" -#include "std_msgs/msg/bool.hpp" -#include "std_msgs/msg/u_int64.hpp" -#include "std_msgs/msg/float64.hpp" - -namespace kuka_sunrise -{ - -RobotCommander::RobotCommander( - KUKA::FRI::LBRCommand & robot_command, - const KUKA::FRI::LBRState & robot_state) -: robot_command_(robot_command), robot_state_(robot_state), torque_command_mode_(false), - ros_clock_(RCL_ROS_TIME) -{ - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - auto callback = - [this](sensor_msgs::msg::JointState::ConstSharedPtr msg) -> void - {this->commandReceivedCallback(msg);}; - // TODO(resizoltan) use TLSFAllocator? implement static strategy for jointstatemsg? - auto msg_strategy = std::make_shared>(); - - auto command_srv_callback = [this]( - std_srvs::srv::SetBool::Request::SharedPtr request, - std_srvs::srv::SetBool::Response::SharedPtr response) { - if (this->setTorqueCommanding(request->data)) { - response->success = true; - } else { - response->success = false; - } - }; - - // TODO(Svastits): create service for command mode changes - /*set_command_mode_service_ = robot_control_node_->create_service( - "set_command_mode", command_srv_callback);*/ -} - -void RobotCommander::addBooleanOutputCommander(const std::string & name) -{ - // TODO(Svastits): add to command interfaces - - /*if (robot_control_node_->get_current_state().label() != "unconfigured") { - return; // TODO(resizoltan) handle other states - } - auto output_setter_func = [this](std::string name, bool value) -> void { - return this->robot_command_.setBooleanIOValue(name.c_str(), value); - }; - output_subscriptions_.emplace_back( - std::make_unique>( - name, output_setter_func, - is_active_, - robot_control_node_));*/ -} - -void RobotCommander::addDigitalOutputCommander(const std::string & name) -{ - // TODO(Svastits): add to command interfaces - - /*if (robot_control_node_->get_current_state().label() != "unconfigured") { - return; // TODO(resizoltan) handle other states - } - auto output_setter_func = [this](std::string name, uint64_t value) -> void { - return this->robot_command_.setDigitalIOValue(name.c_str(), value); - }; - output_subscriptions_.emplace_back( - std::make_unique>( - name, output_setter_func, is_active_, robot_control_node_));*/ -} - -void RobotCommander::addAnalogOutputCommander(const std::string & name) -{ - // TODO(Svastits): add to command interfaces - - /*if (robot_control_node_->get_current_state().label() != "unconfigured") { - return; // TODO(resizoltan) handle other states - } - auto output_setter_func = [this](std::string name, double value) -> void { - return this->robot_command_.setAnalogIOValue(name.c_str(), value); - }; - output_subscriptions_.emplace_back( - std::make_unique>( - name, output_setter_func, - is_active_, - robot_control_node_));*/ -} - -bool RobotCommander::setTorqueCommanding(bool is_torque_mode_active) -{ - if (!is_active_) { - torque_command_mode_ = is_torque_mode_active; - return true; - } else { - return false; - } -} - -void RobotCommander::updateCommand(const rclcpp::Time & stamp) -{ - if (!is_active_) { - printf("robot commander deactivated, exiting updatecommand\n"); - return; - } - - if (torque_command_mode_) { - if (joint_command_msg_->effort.empty()) { - // raise some error/warning - printf("Effort of joint command msg is empty in torque command mode\n"); - return; - } - const double * joint_torques_ = joint_command_msg_->effort.data(); - robot_command_.setJointPosition(robot_state_.getIpoJointPosition()); - robot_command_.setTorque(joint_torques_); - } else { - if (joint_command_msg_->position.empty()) { - // raise some error/warning - printf("Position of joint command msg is empty in position command mode\n"); - return; - } - const double * joint_positions_ = joint_command_msg_->position.data(); - robot_command_.setJointPosition(joint_positions_); - } - - for (auto & output_subscription : output_subscriptions_) { - output_subscription->updateOutput(); - } -} - - -bool RobotCommander::deactivate() -{ - is_active_ = false; - return true; -} - -} // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp deleted file mode 100644 index d2123e41..00000000 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_control_node.cpp +++ /dev/null @@ -1,169 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include "kuka_sunrise/robot_control_node.hpp" -#include "lifecycle_msgs/msg/state.hpp" - -namespace kuka_sunrise -{ - -RobotControlNode::RobotControlNode() -: kroshu_ros2_core::ROS2BaseLCNode("robot_control"), close_requested_(false) -{ - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.reliable(); - auto command_srv_callback = [this]( - std_srvs::srv::SetBool::Request::SharedPtr request, - std_srvs::srv::SetBool::Response::SharedPtr response) { - if (request->data == true) { - response->success = this->activate(); - } else { - response->success = this->deactivate(); - } - }; - - - auto get_fri_state_callback = [this]( - const kuka_sunrise_interfaces::srv::GetState::Request::SharedPtr, - kuka_sunrise_interfaces::srv::GetState::Response::SharedPtr response) { - response->data = client_->robotState().getSessionState(); - }; - - set_commanding_state_service_ = this->create_service( - "robot_control/set_commanding_state", command_srv_callback); - - get_fri_state_service_ = this->create_service( - "robot_control/get_fri_state", get_fri_state_callback); -} - -void RobotControlNode::runClientApplication() -{ - // client_application_->connect(30200, NULL); - bool success = true; - while (success && !close_requested_.load()) { - // success = client_application_->step(); - - if (client_->robotState().getSessionState() == KUKA::FRI::IDLE) { - break; - } - } - if (!success) { - // TODO(resizoltan) handle - } -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn -RobotControlNode::on_configure(const rclcpp_lifecycle::State &) -{ - // client_ = std::make_unique(); - - // TODO(resizoltan) change stack size with setrlimit rlimit_stack? - if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) { - RCLCPP_ERROR(get_logger(), "mlockall error"); - RCLCPP_ERROR(get_logger(), strerror(errno)); - return ERROR; - } - - struct sched_param param; - param.sched_priority = 90; - if (sched_setscheduler(0, SCHED_FIFO, ¶m) == -1) { - RCLCPP_ERROR(get_logger(), "setscheduler error"); - RCLCPP_ERROR(get_logger(), strerror(errno)); - - if (munlockall() == -1) { - RCLCPP_ERROR(get_logger(), "munlockall error"); - } - return ERROR; - } - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn -RobotControlNode::on_cleanup(const rclcpp_lifecycle::State &) -{ - if (munlockall() == -1) { - RCLCPP_ERROR(get_logger(), "munlockall error"); - return ERROR; - } - // client_.reset(); - return SUCCESS; -} - - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn -RobotControlNode::on_activate(const rclcpp_lifecycle::State &) -{ - // client_application_ = std::make_unique - // (udp_connection_, *client_); - client_application_thread_ = std::make_unique(); - - auto run_app = [](void * robot_control_node) -> void * { - static_cast(robot_control_node)->runClientApplication(); - return nullptr; - }; - - if (pthread_create(client_application_thread_.get(), nullptr, run_app, this)) { - RCLCPP_ERROR(get_logger(), "pthread_create error"); - RCLCPP_ERROR(get_logger(), strerror(errno)); - return ERROR; - } - - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn -RobotControlNode::on_deactivate(const rclcpp_lifecycle::State &) -{ - if (this->isActive()) { - this->deactivate(); - } - close_requested_.store(true); - pthread_join(*client_application_thread_, NULL); // TODO(resizoltan) can hang here, apply timeout - close_requested_.store(false); - // client_application_->disconnect(); - // client_application_.reset(); - client_application_thread_.reset(); - return SUCCESS; -} - -bool RobotControlNode::activate() -{ - this->ActivatableInterface::activate(); - // return client_->activate(); - return true; -} - -bool RobotControlNode::deactivate() -{ - this->ActivatableInterface::deactivate(); - // return client_->deactivate(); - return true; -} - -} // namespace kuka_sunrise - -int main(int argc, char * argv[]) -{ - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node->get_node_base_interface()); - executor.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp deleted file mode 100644 index b1489740..00000000 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_observer.cpp +++ /dev/null @@ -1,147 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include - -#include "rclcpp/time.hpp" - -#include "kuka_sunrise/robot_observer.hpp" - -namespace kuka_sunrise -{ - -void RobotObserver::addBooleanInputObserver(std::string name) -{ - // TODO(Svastits): add to state interfaces - - /*if (robot_control_node_->get_current_state().label() != "unconfigured") { - return; // TODO(resizoltan) handle other states - } - auto input_getter_func = [this](std::string name) -> bool { - return this->robot_state_.getBooleanIOValue(name.c_str()); - }; - input_publishers_.emplace_back( - std::make_unique>( - name, - input_getter_func, robot_control_node_));*/ -} - -void RobotObserver::addDigitalInputObserver(std::string name) -{ - // TODO(Svastits): add to state interfaces - - /*if (robot_control_node_->get_current_state().label() != "unconfigured") { - return; // TODO(resizoltan) handle other states - } - auto input_getter_func = [this](std::string name) -> uint64_t { - return this->robot_state_.getDigitalIOValue(name.c_str()); - }; - input_publishers_.emplace_back( - std::make_unique>( - name, - input_getter_func, robot_control_node_));*/ -} - -void RobotObserver::addAnalogInputObserver(std::string name) -{ - // TODO(Svastits): add to state interfaces - - /*if (robot_control_node_->get_current_state().label() != "unconfigured") { - return; // TODO(resizoltan) handle other states - } - auto input_getter_func = [this](std::string name) -> double { - return this->robot_state_.getDigitalIOValue(name.c_str()); - }; - input_publishers_.emplace_back( - std::make_unique>( - name, - input_getter_func, robot_control_node_));*/ -} - -bool RobotObserver::activate() -{ - this->ActivatableInterface::activate(); - joint_state_publisher_->on_activate(); - tracking_performance_publisher_->on_activate(); - return true; -} - -bool RobotObserver::deactivate() -{ - this->ActivatableInterface::deactivate(); - joint_state_publisher_->on_deactivate(); - tracking_performance_publisher_->on_deactivate(); - return true; -} - -RobotObserver::RobotObserver( - const KUKA::FRI::LBRState & robot_state) -: robot_state_(robot_state) -{ - joint_state_msg_.position.reserve(robot_state_.NUMBER_OF_JOINTS); - joint_state_msg_.velocity.reserve(robot_state_.NUMBER_OF_JOINTS); - joint_state_msg_.effort.reserve(robot_state_.NUMBER_OF_JOINTS); - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - // TODO(Svastits): add to state interface - /*tracking_performance_publisher_ = robot_control_node->create_publisher< - std_msgs::msg::Float64>("tracking_performance", qos);*/ -} - -void RobotObserver::publishRobotState(const rclcpp::Time & stamp) -{ - /*if (robot_control_node_->get_current_state().label() != "inactive" && - robot_control_node_->get_current_state().label() != "active") - { - return; // TODO(resizoltan) handle other states - }*/ - - joint_state_msg_.header.frame_id = "world"; - joint_state_msg_.header.stamp = stamp; // TODO(resizoltan) catch exceptions - - if (robot_state_.getSessionState() == KUKA::FRI::COMMANDING_WAIT || - robot_state_.getSessionState() == KUKA::FRI::COMMANDING_ACTIVE) - { - joint_state_msg_.name = std::vector {"URDFLBRiiwa14Joint1", - "URDFLBRiiwa14Joint2", "URDFLBRiiwaJoint3", "URDFLBRiiwaJoint4", - "URDFLBRiiwaJoint5", "URDFLBRiiwaJoint6", "URDFLBRiiwaJoint7"}; - const double * joint_positions_measured = - robot_state_.getMeasuredJointPosition(); - // TODO(resizoltan) external vs measured torque? - - const double * joint_torques_external = robot_state_.getExternalTorque(); - joint_state_msg_.velocity.clear(); - joint_state_msg_.position.assign( - joint_positions_measured, - joint_positions_measured + robot_state_.NUMBER_OF_JOINTS); - joint_state_msg_.effort.assign( - joint_torques_external, - joint_torques_external + robot_state_.NUMBER_OF_JOINTS); - joint_state_publisher_->publish(joint_state_msg_); - const double & tracking_performance = robot_state_.getTrackingPerformance(); - std_msgs::msg::Float64 tracking_perf_msg; - tracking_perf_msg.data = tracking_performance; - tracking_performance_publisher_->publish(tracking_perf_msg); - } - // TODO(resizoltan) double check this: - for (auto i = std::next(input_publishers_.begin()); - i != input_publishers_.end(); i++) - { - (*i)->publishInputValue(); - } -} - -} // namespace kuka_sunrise From d46de14db1c17dde65a947676767033ff39b67c8 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 16:20:37 +0200 Subject: [PATCH 30/94] lint, uncrustify, copyright --- .../src/robot_state_broadcaster.cpp | 3 +- kuka_sunrise_driver/CMakeLists.txt | 9 ++--- .../kuka_fri_hardware_interface.hpp | 11 +++--- kuka_sunrise_driver/launch/basic_launch.py | 34 ++++++++++++++----- .../launch/kuka_sunrise.launch.py | 4 +-- .../launch/kuka_sunrise_control.launch.py | 32 ++++++++++++----- .../kuka_sunrise/configuration_manager.cpp | 3 +- .../kuka_fri_hardware_interface.cpp | 6 ++-- .../src/kuka_sunrise/robot_manager_node.cpp | 3 +- 9 files changed, 72 insertions(+), 33 deletions(-) diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp index a0522338..fd3ffca8 100644 --- a/kuka_controllers/src/robot_state_broadcaster.cpp +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -26,7 +26,8 @@ controller_interface::CallbackReturn RobotStateBroadcaster::on_init() return controller_interface::CallbackReturn::SUCCESS; } -controller_interface::InterfaceConfiguration RobotStateBroadcaster::command_interface_configuration() +controller_interface::InterfaceConfiguration +RobotStateBroadcaster::command_interface_configuration() const { return controller_interface::InterfaceConfiguration{controller_interface:: diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index c292a52c..492e9d43 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -48,11 +48,11 @@ add_library(robot_manager SHARED src/kuka_sunrise/robot_manager.cpp src/kuka_sunrise/tcp_connection.cpp) -add_library(robot_control_client SHARED +add_library(kuka_fri_hw_interface SHARED src/kuka_sunrise/kuka_fri_hardware_interface.cpp ) -ament_target_dependencies(robot_control_client kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs sensor_msgs std_srvs hardware_interface) -target_link_libraries(robot_control_client fri::fri_client) +ament_target_dependencies(kuka_fri_hw_interface kuka_sunrise_interfaces rclcpp rclcpp_lifecycle hardware_interface) +target_link_libraries(kuka_fri_hw_interface fri::fri_client) add_library(configuration_manager SHARED src/kuka_sunrise/configuration_manager.cpp) @@ -84,7 +84,8 @@ ament_target_dependencies(lifecycle_client_node rclcpp rclcpp_lifecycle std_msgs pluginlib_export_plugin_description_file(hardware_interface hardware_interface.xml) -install(TARGETS robot_manager robot_control_client robot_manager_node position_controller_node torque_controller_node lifecycle_client_node sunrise_control_node +install(TARGETS robot_manager kuka_fri_hw_interface robot_manager_node position_controller_node torque_controller_node + lifecycle_client_node sunrise_control_node DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index bdcef4e6..79c11e6c 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef KUKA_SUNRISE__ROBOT_CONTROL_CLIENT_HPP_ -#define KUKA_SUNRISE__ROBOT_CONTROL_CLIENT_HPP_ +#ifndef KUKA_SUNRISE__KUKA_FRI_HARDWARE_INTERFACE_HPP_ +#define KUKA_SUNRISE__KUKA_FRI_HARDWARE_INTERFACE_HPP_ #include #include @@ -36,11 +36,12 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface namespace kuka_sunrise { -class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, +class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, + public KUKA::FRI::LBRClient, public ActivatableInterface { public: - KUKAFRIHardwareInterface() + KUKAFRIHardwareInterface() : client_application_(udp_connection_, *this) {} ~KUKAFRIHardwareInterface(); bool setReceiveMultiplier(int receive_multiplier); @@ -89,4 +90,4 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, pub } // namespace kuka_sunrise -#endif // KUKA_SUNRISE__ROBOT_CONTROL_CLIENT_HPP_ +#endif // KUKA_SUNRISE__KUKA_FRI_HARDWARE_INTERFACE_HPP_ diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index 9c0ffd7f..9c3b1b38 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -1,3 +1,17 @@ +# Copyright 2022 Ãron Svastits +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import os from ament_index_python.packages import get_package_share_directory @@ -5,22 +19,26 @@ from launch import LaunchDescription from launch_ros.actions import Node + def load_file(absolute_file_path): try: with open(absolute_file_path, 'r') as file: return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available return None def generate_launch_description(): - controller_config = get_package_share_directory('kuka_lbr_iiwa7_support') + "/config/iiwa_ros2_controller_config.yaml" - forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" - robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/urdflbriiwa7.urdf") - robot_description = {'robot_description' : robot_description_config} + controller_config = (get_package_share_directory('kuka_lbr_iiwa7_support') + + "/config/iiwa_ros2_controller_config.yaml") + forward_controller_config = (get_package_share_directory('kuka_sunrise') + + "/config/forward_controller.yaml") + robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + + "/urdf/urdflbriiwa7.urdf") + robot_description = {'robot_description': robot_description_config} - rviz_config_file = os.path.join( - get_package_share_directory('kuka_lbr_iiwa7_support'), 'launch', 'urdf.rviz') + rviz_config_file = os.path.join(get_package_share_directory('kuka_lbr_iiwa7_support'), + 'launch', 'urdf.rviz') return LaunchDescription([ Node( @@ -52,4 +70,4 @@ def generate_launch_description(): output='both', parameters=[robot_description] ), - ]) \ No newline at end of file + ]) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py index a4a0405c..8232bdca 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py @@ -20,9 +20,9 @@ def generate_launch_description(): return LaunchDescription([ launch_ros.actions.LifecycleNode( - namespace = '', package='kuka_sunrise', executable='robot_manager_node', output='screen', + namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', name=['robot_manager'], parameters=[{'controller_ip': ''}]), launch_ros.actions.LifecycleNode( - namespace = '', package='kuka_sunrise', executable='robot_control_node', output='screen', + namespace='', package='kuka_sunrise', executable='robot_control_node', output='screen', name=['robot_control']) ]) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index c3bf59cf..b818fde6 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -1,4 +1,16 @@ -import os +# Copyright 2022 Ãron Svastits +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from ament_index_python.packages import get_package_share_directory @@ -6,19 +18,23 @@ from launch_ros.actions import Node from launch_ros.actions import LifecycleNode + def load_file(absolute_file_path): try: with open(absolute_file_path, 'r') as file: return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available return None def generate_launch_description(): - controller_config = get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml" - forward_controller_config = get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml" - robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/urdflbriiwa7.urdf") - robot_description = {'robot_description' : robot_description_config} + controller_config = (get_package_share_directory('kuka_sunrise') + + "/config/iiwa_ros2_controller_config.yaml") + forward_controller_config = (get_package_share_directory('kuka_sunrise') + + "/config/forward_controller.yaml") + robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + + "/urdf/urdflbriiwa7.urdf") + robot_description = {'robot_description': robot_description_config} return LaunchDescription([ Node( @@ -27,7 +43,7 @@ def generate_launch_description(): parameters=[robot_description, controller_config] ), LifecycleNode( - namespace = '', package='kuka_sunrise', executable='robot_manager_node', output='screen', + namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', name=['robot_manager'], parameters=[{'controller_ip': ''}] ), Node( @@ -51,4 +67,4 @@ def generate_launch_description(): executable="spawner", arguments=["robot_state_broadcaster", "-c", "/controller_manager"] ) - ]) \ No newline at end of file + ]) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index b6bb03f6..258453b4 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -199,8 +199,7 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr bool ConfigurationManager::setCommandMode(const std::string & control_mode) const { - - //TODO(Svastits): load and switch controllers through controller_manager + // TODO(Svastits): load and switch controllers through controller_manager ClientCommandModeID client_command_mode; if (control_mode == "position") { client_command_mode = POSITION_COMMAND_MODE; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 992abf1f..f993eeb0 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -18,7 +18,8 @@ namespace kuka_sunrise { -CallbackReturn KUKAFRIHardwareInterface::on_init(const hardware_interface::HardwareInfo & system_info) +CallbackReturn KUKAFRIHardwareInterface::on_init( + const hardware_interface::HardwareInfo & system_info) { if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; @@ -222,7 +223,8 @@ std::vector KUKAFRIHardwareInterface::export return state_interfaces; } -std::vector KUKAFRIHardwareInterface::export_command_interfaces() +std::vector KUKAFRIHardwareInterface:: +export_command_interfaces() { RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_command_interfaces()"); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 03bf300f..ea89f441 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -64,7 +64,8 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) { auto result = SUCCESS; - // TODO(Svastits): configure HWInterface and controllers (currently done from launch file after loading) + // TODO(Svastits): configure HWInterface and controllers + // (currently done from launch file after loading) // If this fails, the node should be restarted, with different parameter values // Therefore exceptions are not caught if (!configuration_manager_) { From 08e73ace71ea4ee2157c80f0895d5bfde590bda1 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 13 Jul 2022 16:40:12 +0200 Subject: [PATCH 31/94] uncrustify --- .../robot_control/src/robot_control/joint_controller_base.cpp | 2 +- .../teleop_guided_robot/launch/keyboard_guided_robot.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_control/robot_control/src/robot_control/joint_controller_base.cpp b/kuka_sunrise_control/robot_control/src/robot_control/joint_controller_base.cpp index 20f7ad10..3ae8fea9 100644 --- a/kuka_sunrise_control/robot_control/src/robot_control/joint_controller_base.cpp +++ b/kuka_sunrise_control/robot_control/src/robot_control/joint_controller_base.cpp @@ -233,7 +233,7 @@ bool JointControllerBase::onVelocityFactorsChangeRequest( void JointControllerBase::updateMaxPositionDifference() { - auto calc_pos_diff = [ & loop_period_ms_ = loop_period_ms_](double v) { + auto calc_pos_diff = [&loop_period_ms_ = loop_period_ms_](double v) { return v * loop_period_ms_ / JointControllerBase::ms_in_sec_; }; std::transform( diff --git a/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py b/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py index 7cc2b804..b3ee3eb6 100644 --- a/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py +++ b/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py @@ -43,7 +43,7 @@ def generate_launch_description(): system_manager = launch_ros.actions.LifecycleNode( namespace="", name='system_manager', - package='teleop_guided_robot', executable='system_manager', output='screen' + package='teleop_guided_robot', executable='system_manager', output='screen' ) """ key_teleop = launch_ros.actions.Node( From e714f5700bbe24da1abb257d61d0d476c2e2502f Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 14 Jul 2022 10:17:33 +0200 Subject: [PATCH 32/94] code cleanup, add external torque interface --- kuka_sunrise_driver/hardware_interface.xml | 2 +- .../kuka_fri_hardware_interface.hpp | 41 ++++++------ .../kuka_fri_hardware_interface.cpp | 66 +++++++------------ 3 files changed, 48 insertions(+), 61 deletions(-) diff --git a/kuka_sunrise_driver/hardware_interface.xml b/kuka_sunrise_driver/hardware_interface.xml index 571e99f6..18c4ced8 100644 --- a/kuka_sunrise_driver/hardware_interface.xml +++ b/kuka_sunrise_driver/hardware_interface.xml @@ -1,5 +1,5 @@ - + diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 79c11e6c..044791a4 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -30,6 +30,8 @@ #include "fri/HWIFClientApplication.hpp" #include "fri/friUdpConnection.h" +#include "pluginlib/class_list_macros.hpp" + using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; @@ -38,22 +40,19 @@ namespace kuka_sunrise class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, - public ActivatableInterface + public ActivatableInterface // TODO(Svastits): is this necessary in current state? { public: KUKAFRIHardwareInterface() : client_application_(udp_connection_, *this) {} - ~KUKAFRIHardwareInterface(); - bool setReceiveMultiplier(int receive_multiplier); - - virtual void waitForCommand(); - virtual void command(); - CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; + std::vector export_state_interfaces() override; + std::vector export_command_interfaces() override; + hardware_interface::return_type read( const rclcpp::Time & time, const rclcpp::Duration & period) override; @@ -62,32 +61,36 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, const rclcpp::Duration & period) override; void updateCommand(const rclcpp::Time & stamp); + bool setReceiveMultiplier(int receive_multiplier); + + void waitForCommand() final; + void command() final; + - std::vector export_state_interfaces() override; - std::vector export_command_interfaces() override; private: - // rclcpp_lifecycle::LifecycleNode::SharedPtr robot_control_node_; + KUKA::FRI::HWIFClientApplication client_application_; + KUKA::FRI::UdpConnection udp_connection_; + rclcpp::Service::SharedPtr set_receive_multiplier_service_; rclcpp::Clock ros_clock_; // Command interface must be of type double, but controller can set only integers + // this is a temporary solution, until runtime parameters are supported for hardware interfaces double receive_multiplier_ = 1; int receive_counter_ = 0; - - // Store the command for the simulated robot - std::vector hw_commands_, hw_states_; - std::vector hw_torques_, hw_effort_command_; - - KUKA::FRI::HWIFClientApplication client_application_; - KUKA::FRI::UdpConnection udp_connection_; - bool torque_command_mode_ = false; + + // State and command interfaces + std::vector hw_commands_; + std::vector hw_states_; + std::vector hw_torques_ext_; + std::vector hw_torques_; + std::vector hw_effort_command_; double tracking_performance_ = 1; double fri_state_ = 0; double connection_quality_ = 0; }; - } // namespace kuka_sunrise #endif // KUKA_SUNRISE__KUKA_FRI_HARDWARE_INTERFACE_HPP_ diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index f993eeb0..616eaa1d 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -27,6 +27,7 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( hw_states_.resize(info_.joints.size()); hw_commands_.resize(info_.joints.size()); hw_torques_.resize(info_.joints.size()); + hw_torques_ext_.resize(info_.joints.size()); hw_effort_command_.resize(info_.joints.size()); for (const hardware_interface::ComponentInfo & joint : info_.joints) { @@ -51,8 +52,8 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( return CallbackReturn::ERROR; } - if (joint.state_interfaces.size() != 2) { - RCLCPP_FATAL(rclcpp::get_logger("RobotControlClient"), "expecting exactly 2 state interface"); + if (joint.state_interfaces.size() != 3) { + RCLCPP_FATAL(rclcpp::get_logger("RobotControlClient"), "expecting exactly 3 state interface"); return CallbackReturn::ERROR; } @@ -69,7 +70,13 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( "RobotControlClient"), "expecting EFFORT state interface as second"); return CallbackReturn::ERROR; } - // TODO(Svastits): add external torque interface to URDF and check it here + + if (joint.state_interfaces[2].name != "external_torque") { + RCLCPP_FATAL( + rclcpp::get_logger( + "RobotControlClient"), "expecting 'external torque' state interface as third"); + return CallbackReturn::ERROR; + } } return CallbackReturn::SUCCESS; @@ -99,10 +106,6 @@ CallbackReturn KUKAFRIHardwareInterface::on_deactivate(const rclcpp_lifecycle::S return CallbackReturn::SUCCESS; } -KUKAFRIHardwareInterface::~KUKAFRIHardwareInterface() -{ -} - void KUKAFRIHardwareInterface::waitForCommand() { // TODO(Svastits): is this really the purpose of waitForCommand? @@ -143,14 +146,13 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( hw_states_.assign(position, position + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); const double * torque = robotState().getMeasuredTorque(); hw_torques_.assign(torque, torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + const double* external_torque = robotState().getExternalTorque(); + hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); tracking_performance_ = robotState().getTrackingPerformance(); fri_state_ = robotState().getSessionState(); connection_quality_ = robotState().getConnectionQuality(); - // const double* external_torque = robotState().getExternalTorque(); - // hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); - // TODO(Svastits): add external torque interface return hardware_interface::return_type::OK; } @@ -197,28 +199,21 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) std::vector KUKAFRIHardwareInterface::export_state_interfaces() { - RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_state_interfaces()"); - std::vector state_interfaces; - state_interfaces.emplace_back( - hardware_interface::StateInterface("state", "fri_state", &fri_state_)); - - state_interfaces.emplace_back( - hardware_interface::StateInterface("state", "connection_quality", &connection_quality_)); + state_interfaces.emplace_back("state", "fri_state", &fri_state_); + state_interfaces.emplace_back("state", "connection_quality", &connection_quality_); for (size_t i = 0; i < info_.joints.size(); i++) { state_interfaces.emplace_back( - hardware_interface::StateInterface( - info_.joints[i].name, - hardware_interface::HW_IF_POSITION, - &hw_states_[i])); + info_.joints[i].name, hardware_interface::HW_IF_POSITION, + &hw_states_[i]); state_interfaces.emplace_back( - hardware_interface::StateInterface( - info_.joints[i].name, - hardware_interface::HW_IF_EFFORT, - &hw_torques_[i])); + info_.joints[i].name, hardware_interface::HW_IF_EFFORT, + &hw_torques_[i]); + + state_interfaces.emplace_back(info_.joints[i].name, "external_torque", &hw_torques_ext_[i]); } return state_interfaces; } @@ -226,32 +221,21 @@ std::vector KUKAFRIHardwareInterface::export std::vector KUKAFRIHardwareInterface:: export_command_interfaces() { - RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "export_command_interfaces()"); - std::vector command_interfaces; - command_interfaces.emplace_back( - hardware_interface::CommandInterface("timing", "receive_multiplier", &receive_multiplier_)); + command_interfaces.emplace_back("timing", "receive_multiplier", &receive_multiplier_); for (size_t i = 0; i < info_.joints.size(); i++) { command_interfaces.emplace_back( - hardware_interface::CommandInterface( - info_.joints[i].name, - hardware_interface::HW_IF_POSITION, - &hw_commands_[i])); - + info_.joints[i].name, hardware_interface::HW_IF_POSITION, + &hw_commands_[i]); command_interfaces.emplace_back( - hardware_interface::CommandInterface( - info_.joints[i].name, - hardware_interface::HW_IF_EFFORT, - &hw_effort_command_[i])); + info_.joints[i].name, hardware_interface::HW_IF_EFFORT, + &hw_effort_command_[i]); } return command_interfaces; } } // namespace kuka_sunrise -#include "pluginlib/class_list_macros.hpp" - - PLUGINLIB_EXPORT_CLASS( kuka_sunrise::KUKAFRIHardwareInterface, hardware_interface::SystemInterface From 5661e9c4823d0d692c4f2e5a31bbc9fc063bd55c Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 14 Jul 2022 10:18:54 +0200 Subject: [PATCH 33/94] uncrustify --- .../include/kuka_sunrise/kuka_fri_hardware_interface.hpp | 2 -- .../src/kuka_sunrise/kuka_fri_hardware_interface.cpp | 4 ++-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 044791a4..e5443158 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -66,8 +66,6 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, void waitForCommand() final; void command() final; - - private: KUKA::FRI::HWIFClientApplication client_application_; KUKA::FRI::UdpConnection udp_connection_; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 616eaa1d..fc15a3e4 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -146,8 +146,8 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( hw_states_.assign(position, position + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); const double * torque = robotState().getMeasuredTorque(); hw_torques_.assign(torque, torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); - const double* external_torque = robotState().getExternalTorque(); - hw_torques_ext_.assign(external_torque, external_torque+KUKA::FRI::LBRState::NUMBER_OF_JOINTS); + const double * external_torque = robotState().getExternalTorque(); + hw_torques_ext_.assign(external_torque, external_torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); tracking_performance_ = robotState().getTrackingPerformance(); fri_state_ = robotState().getSessionState(); From db9b1507c261aac1dd17eda7ad5bf067ff15497b Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 14 Jul 2022 12:34:53 +0200 Subject: [PATCH 34/94] add basic IO access --- .../kuka_fri_hardware_interface.hpp | 2 ++ .../kuka_fri_hardware_interface.cpp | 31 ++++++++++++++++--- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index e5443158..07421c7f 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -88,6 +88,8 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, double tracking_performance_ = 1; double fri_state_ = 0; double connection_quality_ = 0; + std::vector gpio_inputs_; + std::vector gpio_outputs_; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index fc15a3e4..6d78b267 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -30,6 +30,12 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( hw_torques_ext_.resize(info_.joints.size()); hw_effort_command_.resize(info_.joints.size()); + + // TODO(Svastits): create config file for available I/O with types + // and implement classes for different data types + gpio_inputs_.resize(10); + gpio_outputs_.resize(10); + for (const hardware_interface::ComponentInfo & joint : info_.joints) { if (joint.command_interfaces.size() != 2) { RCLCPP_FATAL( @@ -153,6 +159,9 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( fri_state_ = robotState().getSessionState(); connection_quality_ = robotState().getConnectionQuality(); + for (size_t i = 0; i < gpio_inputs_.size(); ++i) { + gpio_inputs_[i] = robotState().getBooleanIOValue(("Output" + std::to_string(i)).c_str()); + } return hardware_interface::return_type::OK; } @@ -189,12 +198,12 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) const double * joint_positions_ = hw_commands_.data(); robotCommand().setJointPosition(joint_positions_); } - // TODO(Svastits): setDigitalIOValue and setAnalogIOValue -/* - for (auto & output_subscription : output_subscriptions_) { - output_subscription->updateOutput(); + + for (size_t i = 0; i < gpio_inputs_.size(); ++i) { + robotCommand().setBooleanIOValue( + ("Input" + std::to_string(i)).c_str(), + static_cast(gpio_inputs_[i])); } - */ } std::vector KUKAFRIHardwareInterface::export_state_interfaces() @@ -204,6 +213,12 @@ std::vector KUKAFRIHardwareInterface::export state_interfaces.emplace_back("state", "fri_state", &fri_state_); state_interfaces.emplace_back("state", "connection_quality", &connection_quality_); + + // Register I/O outputs (read access) and inputs (write access) + for (size_t i = 0; i < gpio_outputs_.size(); ++i) { + state_interfaces.emplace_back("gpio", "Output" + std::to_string(i), &gpio_outputs_[i]); + } + for (size_t i = 0; i < info_.joints.size(); i++) { state_interfaces.emplace_back( info_.joints[i].name, hardware_interface::HW_IF_POSITION, @@ -224,6 +239,12 @@ export_command_interfaces() std::vector command_interfaces; command_interfaces.emplace_back("timing", "receive_multiplier", &receive_multiplier_); + + // Register I/O inputs (write access) + for (size_t i = 0; i < gpio_outputs_.size(); ++i) { + command_interfaces.emplace_back("gpio", "Input" + std::to_string(i), &gpio_inputs_[i]); + } + for (size_t i = 0; i < info_.joints.size(); i++) { command_interfaces.emplace_back( info_.joints[i].name, hardware_interface::HW_IF_POSITION, From 496705ad3abff256f3a43a5bbc2b3009a500aa24 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 14 Jul 2022 13:53:03 +0200 Subject: [PATCH 35/94] add I/O reader and writer classes --- .../kuka_fri_hardware_interface.hpp | 65 ++++++++++++++++++- .../kuka_fri_hardware_interface.cpp | 20 +++--- 2 files changed, 72 insertions(+), 13 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 07421c7f..69d8d947 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -88,8 +88,69 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, double tracking_performance_ = 1; double fri_state_ = 0; double connection_quality_ = 0; - std::vector gpio_inputs_; - std::vector gpio_outputs_; + + enum IOTypes + { + ANALOG = 0, + DIGITAL = 1, + BOOLEAN = 2, + }; + + class GPIOReader + { + const std::string name_; + IOTypes type_; + KUKA::FRI::LBRState state_; + +public: + double data_; + GPIOReader(const std::string & name, IOTypes type, const KUKA::FRI::LBRState & state) + : name_(name), type_(type), state_(state) {} + void getValue() + { + switch (type_) { + case ANALOG: + data_ = state_.getAnalogIOValue(name_.c_str()); + break; + case DIGITAL: + data_ = state_.getDigitalIOValue(name_.c_str()); + break; + case BOOLEAN: + data_ = state_.getBooleanIOValue(name_.c_str()); + break; + } + } + }; + + class GPIOWriter + { + // TODO(Svastits): add default value?? + const std::string name_; + IOTypes type_; + KUKA::FRI::LBRCommand command_; + +public: + double data_; + GPIOWriter(const std::string & name, IOTypes type, KUKA::FRI::LBRCommand & command) + : name_(name), type_(type), command_(command) {} + void setValue() + { + switch (type_) { + case ANALOG: + command_.setAnalogIOValue(name_.c_str(), data_); + break; + case DIGITAL: + command_.setDigitalIOValue(name_.c_str(), data_); + break; + case BOOLEAN: + command_.setBooleanIOValue(name_.c_str(), data_); + break; + } + } + }; + + std::vector gpio_inputs_; + std::vector gpio_outputs_; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 6d78b267..70375b69 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -31,10 +31,10 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( hw_effort_command_.resize(info_.joints.size()); - // TODO(Svastits): create config file for available I/O with types - // and implement classes for different data types - gpio_inputs_.resize(10); - gpio_outputs_.resize(10); + // TODO(Svastits): create config file for available I/O-s with types + // and fill vectors with that info + gpio_inputs_.emplace_back("Input1", BOOLEAN, robotCommand()); + gpio_outputs_.emplace_back("Output1", BOOLEAN, robotState()); for (const hardware_interface::ComponentInfo & joint : info_.joints) { if (joint.command_interfaces.size() != 2) { @@ -159,8 +159,8 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( fri_state_ = robotState().getSessionState(); connection_quality_ = robotState().getConnectionQuality(); - for (size_t i = 0; i < gpio_inputs_.size(); ++i) { - gpio_inputs_[i] = robotState().getBooleanIOValue(("Output" + std::to_string(i)).c_str()); + for (size_t i = 0; i < gpio_outputs_.size(); ++i) { + gpio_outputs_[i].getValue(); } return hardware_interface::return_type::OK; } @@ -200,9 +200,7 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) } for (size_t i = 0; i < gpio_inputs_.size(); ++i) { - robotCommand().setBooleanIOValue( - ("Input" + std::to_string(i)).c_str(), - static_cast(gpio_inputs_[i])); + gpio_inputs_[i].setValue(); } } @@ -216,7 +214,7 @@ std::vector KUKAFRIHardwareInterface::export // Register I/O outputs (read access) and inputs (write access) for (size_t i = 0; i < gpio_outputs_.size(); ++i) { - state_interfaces.emplace_back("gpio", "Output" + std::to_string(i), &gpio_outputs_[i]); + state_interfaces.emplace_back("gpio", "Output" + std::to_string(i), &gpio_outputs_[i].data_); } for (size_t i = 0; i < info_.joints.size(); i++) { @@ -242,7 +240,7 @@ export_command_interfaces() // Register I/O inputs (write access) for (size_t i = 0; i < gpio_outputs_.size(); ++i) { - command_interfaces.emplace_back("gpio", "Input" + std::to_string(i), &gpio_inputs_[i]); + command_interfaces.emplace_back("gpio", "Input" + std::to_string(i), &gpio_inputs_[i].data_); } for (size_t i = 0; i < info_.joints.size(); i++) { From 2c43893b4a9ffd4acdb8f39bf8a5fc4c6edb90fe Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 14 Jul 2022 16:16:52 +0200 Subject: [PATCH 36/94] read gpio config from urdf --- .../kuka_fri_hardware_interface.hpp | 32 ++++++++---- .../kuka_fri_hardware_interface.cpp | 52 +++++++++++++------ 2 files changed, 60 insertions(+), 24 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 69d8d947..45e8985b 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -18,6 +18,8 @@ #include #include #include +#include +#include #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" @@ -32,12 +34,22 @@ #include "pluginlib/class_list_macros.hpp" - using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; namespace kuka_sunrise { +enum IOTypes +{ + ANALOG = 0, + DIGITAL = 1, + BOOLEAN = 2, +}; + +static std::unordered_map const types = +{{"analog", IOTypes::ANALOG}, {"digital", IOTypes::DIGITAL}, {"boolean", IOTypes::BOOLEAN}}; + class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, public KUKA::FRI::LBRClient, public ActivatableInterface // TODO(Svastits): is this necessary in current state? @@ -89,12 +101,13 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, double fri_state_ = 0; double connection_quality_ = 0; - enum IOTypes + IOTypes getType(const std::string type_string) { - ANALOG = 0, - DIGITAL = 1, - BOOLEAN = 2, - }; + auto it = types.find(type_string); + if (it != types.end()) { + return it->second; + } else {throw std::runtime_error("Invalid type for GPIO");} + } class GPIOReader { @@ -124,15 +137,16 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, class GPIOWriter { - // TODO(Svastits): add default value?? const std::string name_; IOTypes type_; KUKA::FRI::LBRCommand command_; public: double data_; - GPIOWriter(const std::string & name, IOTypes type, KUKA::FRI::LBRCommand & command) - : name_(name), type_(type), command_(command) {} + GPIOWriter( + const std::string & name, IOTypes type, KUKA::FRI::LBRCommand & command, + double initial_value) + : name_(name), type_(type), command_(command), data_(initial_value) {} void setValue() { switch (type_) { diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 70375b69..79941cc0 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -30,16 +30,37 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( hw_torques_ext_.resize(info_.joints.size()); hw_effort_command_.resize(info_.joints.size()); + if (info_.gpios.size() != 1) { + RCLCPP_FATAL( + rclcpp::get_logger("KUKAFRIHardwareInterface"), + "expecting exactly 1 GPIO"); + return CallbackReturn::ERROR; + } + + if (info_.gpios[0].command_interfaces.size() > 10 || + info_.gpios[0].state_interfaces.size() > 10) + { + RCLCPP_FATAL( + rclcpp::get_logger("KUKAFRIHardwareInterface"), + "A maximum of 10 inputs and outputs can be registered to FRI"); + return CallbackReturn::ERROR; + } + + for (const auto & state_if : info_.gpios[0].state_interfaces) { + gpio_outputs_.emplace_back(state_if.name, getType(state_if.data_type), robotState()); + } + + for (const auto & command_if : info_.gpios[0].command_interfaces) { + gpio_inputs_.emplace_back( + command_if.name, getType(command_if.data_type), + robotCommand(), std::stod(command_if.initial_value)); + } - // TODO(Svastits): create config file for available I/O-s with types - // and fill vectors with that info - gpio_inputs_.emplace_back("Input1", BOOLEAN, robotCommand()); - gpio_outputs_.emplace_back("Output1", BOOLEAN, robotState()); for (const hardware_interface::ComponentInfo & joint : info_.joints) { if (joint.command_interfaces.size() != 2) { RCLCPP_FATAL( - rclcpp::get_logger("RobotControlClient"), + rclcpp::get_logger("KUKAFRIHardwareInterface"), "expecting exactly 2 command interface"); return CallbackReturn::ERROR; } @@ -47,40 +68,42 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION) { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting POSITION command interface as first"); + "KUKAFRIHardwareInterface"), "expecting POSITION command interface as first"); return CallbackReturn::ERROR; } if (joint.command_interfaces[1].name != hardware_interface::HW_IF_EFFORT) { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting EFFORT command interface as second"); + "KUKAFRIHardwareInterface"), "expecting EFFORT command interface as second"); return CallbackReturn::ERROR; } if (joint.state_interfaces.size() != 3) { - RCLCPP_FATAL(rclcpp::get_logger("RobotControlClient"), "expecting exactly 3 state interface"); + RCLCPP_FATAL( + rclcpp::get_logger( + "KUKAFRIHardwareInterface"), "expecting exactly 3 state interface"); return CallbackReturn::ERROR; } if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting POSITION state interface as first"); + "KUKAFRIHardwareInterface"), "expecting POSITION state interface as first"); return CallbackReturn::ERROR; } if (joint.state_interfaces[1].name != hardware_interface::HW_IF_EFFORT) { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting EFFORT state interface as second"); + "KUKAFRIHardwareInterface"), "expecting EFFORT state interface as second"); return CallbackReturn::ERROR; } if (joint.state_interfaces[2].name != "external_torque") { RCLCPP_FATAL( rclcpp::get_logger( - "RobotControlClient"), "expecting 'external torque' state interface as third"); + "KUKAFRIHardwareInterface"), "expecting 'external torque' state interface as third"); return CallbackReturn::ERROR; } } @@ -95,13 +118,12 @@ CallbackReturn KUKAFRIHardwareInterface::on_configure(const rclcpp_lifecycle::St CallbackReturn KUKAFRIHardwareInterface::on_activate(const rclcpp_lifecycle::State &) { - RCLCPP_INFO(rclcpp::get_logger("HWIF"), "activating client"); if (!client_application_.connect(30200, nullptr)) { - RCLCPP_ERROR(rclcpp::get_logger("HWIF"), "could not connect"); + RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Could not connect"); return CallbackReturn::FAILURE; } this->ActivatableInterface::activate(); - RCLCPP_INFO(rclcpp::get_logger("HWIF"), "activated client"); + RCLCPP_INFO(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Activated client"); return CallbackReturn::SUCCESS; } @@ -170,7 +192,7 @@ hardware_interface::return_type KUKAFRIHardwareInterface::write( const rclcpp::Duration &) { if (!is_active_) { - RCLCPP_INFO(rclcpp::get_logger("RobotControlClient"), "Controller deactivated"); + RCLCPP_INFO(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Controller deactivated"); return hardware_interface::return_type::ERROR; } From 4fdc5c1c1c8368ef8fac174de19951a91052982c Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 15 Jul 2022 10:56:24 +0200 Subject: [PATCH 37/94] add gpio config file --- kuka_sunrise_driver/config/gpio_config.xacro | 48 +++++++++++++++++++ .../launch/kuka_sunrise_control.launch.py | 10 ++-- 2 files changed, 55 insertions(+), 3 deletions(-) create mode 100755 kuka_sunrise_driver/config/gpio_config.xacro diff --git a/kuka_sunrise_driver/config/gpio_config.xacro b/kuka_sunrise_driver/config/gpio_config.xacro new file mode 100755 index 00000000..a8128761 --- /dev/null +++ b/kuka_sunrise_driver/config/gpio_config.xacro @@ -0,0 +1,48 @@ + + + + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + + + + + + + + + + diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index b818fde6..90dfe39c 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -17,6 +17,8 @@ from launch import LaunchDescription from launch_ros.actions import Node from launch_ros.actions import LifecycleNode +from launch_ros.descriptions import ParameterValue +from launch.substitutions import Command def load_file(absolute_file_path): @@ -32,9 +34,11 @@ def generate_launch_description(): "/config/iiwa_ros2_controller_config.yaml") forward_controller_config = (get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml") - robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + - "/urdf/urdflbriiwa7.urdf") - robot_description = {'robot_description': robot_description_config} + robot_description_path = (get_package_share_directory('kuka_lbr_iiwa7_support') + + "/urdf/lbriiwa7.xacro") + robot_description = {'robot_description': ParameterValue( + Command(['xacro ', str(robot_description_path)]), value_type=str + )} return LaunchDescription([ Node( From d7699c256b04c95d427c2d2a858e5b0a673dd6fc Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 15 Jul 2022 11:07:33 +0200 Subject: [PATCH 38/94] update joint names, add joint state pub --- .../config/forward_controller.yaml | 14 +++++++------- kuka_sunrise_driver/launch/basic_launch.py | 19 +++++++++++++++---- 2 files changed, 22 insertions(+), 11 deletions(-) diff --git a/kuka_sunrise_driver/config/forward_controller.yaml b/kuka_sunrise_driver/config/forward_controller.yaml index 5621c023..ad9e286c 100644 --- a/kuka_sunrise_driver/config/forward_controller.yaml +++ b/kuka_sunrise_driver/config/forward_controller.yaml @@ -1,12 +1,12 @@ /forward_command_controller_position: ros__parameters: joints: - - URDFLBRiiwa7Joint1 - - URDFLBRiiwa7Joint2 - - URDFLBRiiwa7Joint3 - - URDFLBRiiwa7Joint4 - - URDFLBRiiwa7Joint5 - - URDFLBRiiwa7Joint6 - - URDFLBRiiwa7Joint7 + - LBRiiwa7Joint1 + - LBRiiwa7Joint2 + - LBRiiwa7Joint3 + - LBRiiwa7Joint4 + - LBRiiwa7Joint5 + - LBRiiwa7Joint6 + - LBRiiwa7Joint7 interface_name: position diff --git a/kuka_sunrise_driver/launch/basic_launch.py b/kuka_sunrise_driver/launch/basic_launch.py index 9c3b1b38..18661dfa 100644 --- a/kuka_sunrise_driver/launch/basic_launch.py +++ b/kuka_sunrise_driver/launch/basic_launch.py @@ -18,6 +18,8 @@ from launch import LaunchDescription from launch_ros.actions import Node +from launch_ros.descriptions import ParameterValue +from launch.substitutions import Command def load_file(absolute_file_path): @@ -29,13 +31,15 @@ def load_file(absolute_file_path): def generate_launch_description(): - controller_config = (get_package_share_directory('kuka_lbr_iiwa7_support') + + controller_config = (get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml") forward_controller_config = (get_package_share_directory('kuka_sunrise') + "/config/forward_controller.yaml") - robot_description_config = load_file(get_package_share_directory('kuka_lbr_iiwa7_support') + - "/urdf/urdflbriiwa7.urdf") - robot_description = {'robot_description': robot_description_config} + robot_description_path = (get_package_share_directory('kuka_lbr_iiwa7_support') + + "/urdf/lbriiwa7.xacro") + robot_description = {'robot_description': ParameterValue( + Command(['xacro ', str(robot_description_path)]), value_type=str + )} rviz_config_file = os.path.join(get_package_share_directory('kuka_lbr_iiwa7_support'), 'launch', 'urdf.rviz') @@ -64,6 +68,13 @@ def generate_launch_description(): output="log", arguments=["-d", rviz_config_file], ), + Node( + package='joint_state_publisher_gui', + executable='joint_state_publisher_gui', + name='joint_state_publisher_gui', + output='both', + parameters=[robot_description] + ), Node( package='robot_state_publisher', executable='robot_state_publisher', From 261fc71827267ab0320aac5f137f78930b555aa6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 15 Jul 2022 15:16:44 +0200 Subject: [PATCH 39/94] add controller lifecycle management --- .../config/iiwa_ros2_controller_config.yaml | 2 +- .../kuka_fri_hardware_interface.hpp | 1 - .../kuka_sunrise/robot_manager_node.hpp | 4 +- .../launch/kuka_sunrise_control.launch.py | 8 +- .../kuka_fri_hardware_interface.cpp | 5 - .../src/kuka_sunrise/robot_manager.cpp | 3 - .../src/kuka_sunrise/robot_manager_node.cpp | 136 +++++++++++++++--- 7 files changed, 122 insertions(+), 37 deletions(-) diff --git a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml index d92e3f38..af5259a0 100755 --- a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml +++ b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml @@ -14,4 +14,4 @@ controller_manager: robot_state_broadcaster: type: kuka_controllers/RobotStateBroadcaster - configure_components_on_start: ["iiwa_hardware"] + configure_components_on_start: [""] diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 45e8985b..b005649a 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -58,7 +58,6 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, KUKAFRIHardwareInterface() : client_application_(udp_connection_, *this) {} CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; - CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index 60bbb858..705c1f27 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -26,7 +26,7 @@ #include "std_srvs/srv/trigger.hpp" #include "std_msgs/msg/bool.hpp" #include "controller_manager_msgs/srv/set_hardware_component_state.hpp" -#include "controller_manager_msgs/srv/configure_start_controller.hpp" +#include "controller_manager_msgs/srv/switch_controller.hpp" #include "kuka_sunrise/robot_manager.hpp" #include "kuka_sunrise/configuration_manager.hpp" @@ -68,7 +68,7 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat rclcpp::Client::SharedPtr set_commanding_state_client_; rclcpp::Client::SharedPtr change_hardware_state_client_; - rclcpp::Client::SharedPtr + rclcpp::Client::SharedPtr change_controller_state_client_; rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp::Service::SharedPtr change_robot_commanding_state_service_; diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 90dfe39c..a46db7e2 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -53,22 +53,22 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--load-only"] + arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--stopped"] ), Node( package="controller_manager", executable="spawner", arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", - forward_controller_config, "--load-only"] + forward_controller_config, "--stopped"] ), Node( package="controller_manager", executable="spawner", - arguments=["timing_controller", "-c", "/controller_manager"] + arguments=["timing_controller", "-c", "/controller_manager", "--stopped"] ), Node( package="controller_manager", executable="spawner", - arguments=["robot_state_broadcaster", "-c", "/controller_manager"] + arguments=["robot_state_broadcaster", "-c", "/controller_manager", "--stopped"] ) ]) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 79941cc0..7503d1cc 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -111,11 +111,6 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( return CallbackReturn::SUCCESS; } -CallbackReturn KUKAFRIHardwareInterface::on_configure(const rclcpp_lifecycle::State &) -{ - return CallbackReturn::SUCCESS; -} - CallbackReturn KUKAFRIHardwareInterface::on_activate(const rclcpp_lifecycle::State &) { if (!client_application_.connect(30200, nullptr)) { diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager.cpp index 9fd9c184..d69b5e64 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager.cpp @@ -142,9 +142,6 @@ bool RobotManager::setFRIConfig(int remote_port, int send_period_ms, int receive msg_size += serializeNext(remote_port, serialized); msg_size += serializeNext(send_period_ms, serialized); msg_size += serializeNext(receive_multiplier, serialized); - for (std::uint8_t byte : serialized) { - printf("%x-", byte); - } return sendCommandAndWait(SET_FRI_CONFIG, serialized); } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index ea89f441..fe1b5c68 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -25,6 +25,16 @@ namespace kuka_sunrise RobotManagerNode::RobotManagerNode() : kroshu_ros2_core::ROS2BaseLCNode("robot_manager") { + // Controllers do not support the cleanup transition (as of now) + // Therefore controllers are loaded and configured at startup, only activation + // and deactivation is managed by this node + // There are two kind of controllers used: + // - RT: joint state broadcaster and joint state/effort commander + // - non-RT: configuration (workaround until runtime parameters are enabled) + // and robot state broadcaster + // RT controllers are started after interface activation + // non-RT controllers are started after interface configuration + setvbuf(stdout, NULL, _IONBF, BUFSIZ); robot_manager_ = std::make_shared( [this] @@ -41,8 +51,8 @@ RobotManagerNode::RobotManagerNode() this->create_client( "controller_manager/set_hardware_component_state", qos.get_rmw_qos_profile(), cbg_); change_controller_state_client_ = - this->create_client( - "controller_manager/configure_and_start_controller", qos.get_rmw_qos_profile(), cbg_); + this->create_client( + "controller_manager/switch_controller", qos.get_rmw_qos_profile(), cbg_); auto command_srv_callback = [this]( std_srvs::srv::SetBool::Request::SharedPtr request, std_srvs::srv::SetBool::Response::SharedPtr response) { @@ -63,9 +73,21 @@ RobotManagerNode::RobotManagerNode() rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) { + // Configure hardware interface + auto hw_request = + std::make_shared(); + hw_request->name = "iiwa_hardware"; + hw_request->target_state.label = "inactive"; + auto hw_response = + kuka_sunrise::sendRequest( + change_hardware_state_client_, hw_request, 0, 2000); + if (!hw_response || !hw_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not configure hardware interface"); + return FAILURE; + } + auto result = SUCCESS; - // TODO(Svastits): configure HWInterface and controllers - // (currently done from launch file after loading) + // If this fails, the node should be restarted, with different parameter values // Therefore exceptions are not caught if (!configuration_manager_) { @@ -73,6 +95,21 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) std::dynamic_pointer_cast( this->shared_from_this()), robot_manager_); } + + // Start non-RT controllers + auto controller_request = + std::make_shared(); + controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + controller_request->start_controllers = + std::vector{"timing_controller", "robot_state_broadcaster"}; + auto controller_response = + kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not start controllers"); + result = FAILURE; + } + const char * controller_ip = this->get_parameter("controller_ip").as_string().c_str(); if (!robot_manager_->isConnected()) { if (!robot_manager_->connect(controller_ip, 30000)) { @@ -111,6 +148,34 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) return ERROR; } + // Stop non-RT controllers + auto controller_request = + std::make_shared(); + controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + controller_request->stop_controllers = + std::vector{"timing_controller", "robot_state_broadcaster"}; + auto controller_response = + kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not stop controllers"); + return ERROR; + } + + // Cleanup hardware interface + // TODO(Svastits): interface cleanup is not called but result is success!! + auto hw_request = + std::make_shared(); + hw_request->name = "iiwa_hardware"; + hw_request->target_state.label = "unconfigured"; + auto hw_response = + kuka_sunrise::sendRequest( + change_hardware_state_client_, hw_request, 0, 2000); + if (!hw_response || !hw_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not cleanup hardware interface"); + return FAILURE; + } + return SUCCESS; } @@ -140,6 +205,7 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) { + // TODO(Svastits): implement rollback mechanism if (!robot_manager_->isConnected()) { RCLCPP_ERROR(get_logger(), "not connected"); return ERROR; @@ -150,8 +216,8 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "could not set fri config"); return FAILURE; } + RCLCPP_INFO(get_logger(), "Successfully set FRI config"); - RCLCPP_INFO(get_logger(), "set FRI config"); // Activate hardware interface auto hw_request = std::make_shared(); @@ -164,7 +230,6 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "Could not activate hardware interface"); return FAILURE; } - RCLCPP_INFO(get_logger(), "Activated LBR iiwa hardware interface"); // Start FRI (in monitoring mode) @@ -172,32 +237,37 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "Could not start FRI"); return FAILURE; } - RCLCPP_INFO(get_logger(), "Started FRI"); // Activate joint state broadcaster + // The other controller must be started later so that it can initialize internal state + // with broadcaster information auto controller_request = - std::make_shared(); - controller_request->name = "joint_state_broadcaster"; + std::make_shared(); + controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + controller_request->start_controllers = std::vector{"joint_state_broadcaster"}; auto controller_response = - kuka_sunrise::sendRequest( + kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); if (!controller_response || !controller_response->ok) { - RCLCPP_ERROR(get_logger(), "Could not activate broadcaster"); + RCLCPP_ERROR(get_logger(), "Could not start controllers"); return FAILURE; } // Activate forward_command_controller // TODO(Svastits): add parameter for controller name - controller_request->name = "forward_command_controller_position"; + controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + controller_request->start_controllers = + std::vector{"forward_command_controller_position"}; controller_response = - kuka_sunrise::sendRequest( + kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); if (!controller_response || !controller_response->ok) { RCLCPP_ERROR(get_logger(), "Could not activate controller"); return FAILURE; } command_state_changed_publisher_->on_activate(); + // Start commanding mode if (!activate()) { return FAILURE; @@ -224,11 +294,32 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) return ERROR; } - if (!requestRobotControlNodeStateTransition( - lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) - { - // TODO(resizoltan) out of sync - RCLCPP_ERROR(get_logger(), "Could not deactivate"); + // Deactivate hardware interface + auto hw_request = + std::make_shared(); + hw_request->name = "iiwa_hardware"; + hw_request->target_state.label = "inactive"; + auto hw_response = + kuka_sunrise::sendRequest( + change_hardware_state_client_, hw_request, 0, 2000); + if (!hw_response || !hw_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not deactivate hardware interface"); + return ERROR; + } + RCLCPP_INFO(get_logger(), "Deactivated LBR iiwa hardware interface"); + + + // Stop RT controllers + auto controller_request = + std::make_shared(); + controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + controller_request->stop_controllers = + std::vector{"joint_state_broadcaster", "forward_command_controller_position"}; + auto controller_response = + kuka_sunrise::sendRequest( + change_controller_state_client_, controller_request, 0, 2000); + if (!controller_response || !controller_response->ok) { + RCLCPP_ERROR(get_logger(), "Could not stop controllers"); return ERROR; } @@ -309,9 +400,12 @@ bool RobotManagerNode::setRobotControlNodeCommandState(bool active) void RobotManagerNode::handleControlEndedError() { // TODO(Svastits): deactivate managers by internal control ended error - // currently only the ActivatableInterface is deactivated - RCLCPP_INFO(get_logger(), "control ended"); - deactivate(); + // currently the hardware interface deactivation fails with timeout + // (possible threading issue) + RCLCPP_INFO(get_logger(), "Control ended"); + if (this->on_deactivate(get_current_state()) != SUCCESS) { + RCLCPP_FATAL(get_logger(), "Could not deactivate managers"); + } } void RobotManagerNode::handleFRIEndedError() From bd654c8a6516e3762140f65411d11dbdf2ce063a Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 18 Jul 2022 14:48:46 +0200 Subject: [PATCH 40/94] fix deprecated names --- .../include/kuka_controllers/timing_controller.hpp | 2 +- .../launch/kuka_sunrise_control.launch.py | 8 ++++---- .../src/kuka_sunrise/robot_manager_node.cpp | 12 +++++++----- 3 files changed, 12 insertions(+), 10 deletions(-) diff --git a/kuka_controllers/include/kuka_controllers/timing_controller.hpp b/kuka_controllers/include/kuka_controllers/timing_controller.hpp index 75b4b62b..4fc62d5a 100644 --- a/kuka_controllers/include/kuka_controllers/timing_controller.hpp +++ b/kuka_controllers/include/kuka_controllers/timing_controller.hpp @@ -53,7 +53,7 @@ class TimingController : public controller_interface::ControllerInterface private: rclcpp::Service::SharedPtr receive_multiplier_service_; int receive_multiplier_ = 1; - bool resend_multiplier_ = true; + bool resend_multiplier_ = false; }; } // namespace kuka_controllers #endif // KUKA_CONTROLLERS__TIMING_CONTROLLER_HPP_ diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index a46db7e2..7affecfa 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -53,22 +53,22 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--stopped"] + arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--inactive"] ), Node( package="controller_manager", executable="spawner", arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", - forward_controller_config, "--stopped"] + forward_controller_config, "--inactive"] ), Node( package="controller_manager", executable="spawner", - arguments=["timing_controller", "-c", "/controller_manager", "--stopped"] + arguments=["timing_controller", "-c", "/controller_manager", "--inactive"] ), Node( package="controller_manager", executable="spawner", - arguments=["robot_state_broadcaster", "-c", "/controller_manager", "--stopped"] + arguments=["robot_state_broadcaster", "-c", "/controller_manager", "--inactive"] ) ]) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index fe1b5c68..c5331d34 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -96,11 +96,13 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) this->shared_from_this()), robot_manager_); } + RCLCPP_INFO(get_logger(), "Successfully set 'controller_ip' parameter" ); + // Start non-RT controllers auto controller_request = std::make_shared(); controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->start_controllers = + controller_request->activate_controllers = std::vector{"timing_controller", "robot_state_broadcaster"}; auto controller_response = kuka_sunrise::sendRequest( @@ -152,7 +154,7 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) auto controller_request = std::make_shared(); controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->stop_controllers = + controller_request->deactivate_controllers = std::vector{"timing_controller", "robot_state_broadcaster"}; auto controller_response = kuka_sunrise::sendRequest( @@ -245,7 +247,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) auto controller_request = std::make_shared(); controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->start_controllers = std::vector{"joint_state_broadcaster"}; + controller_request->activate_controllers = std::vector{"joint_state_broadcaster"}; auto controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); @@ -257,7 +259,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) // Activate forward_command_controller // TODO(Svastits): add parameter for controller name controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->start_controllers = + controller_request->activate_controllers = std::vector{"forward_command_controller_position"}; controller_response = kuka_sunrise::sendRequest( @@ -313,7 +315,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) auto controller_request = std::make_shared(); controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->stop_controllers = + controller_request->deactivate_controllers = std::vector{"joint_state_broadcaster", "forward_command_controller_position"}; auto controller_response = kuka_sunrise::sendRequest( From a1e53065239265fef7860531c7b71cf68e93027b Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 19 Jul 2022 09:46:23 +0200 Subject: [PATCH 41/94] fix cleanup bug --- .../internal/activatable_interface.hpp | 2 +- .../kuka_sunrise/kuka_fri_hardware_interface.cpp | 14 ++++++++------ .../src/kuka_sunrise/robot_manager_node.cpp | 2 -- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/internal/activatable_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/internal/activatable_interface.hpp index e775304a..c17cb76a 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/internal/activatable_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/internal/activatable_interface.hpp @@ -40,7 +40,7 @@ class ActivatableInterface } protected: - bool is_active_; + bool is_active_ = false; }; } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 7503d1cc..4a1d3f06 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -153,14 +153,15 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( const rclcpp::Time &, const rclcpp::Duration &) { + // Read is called in inactive state, check is necessary if (!is_active_) { - RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Controller not active"); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - return hardware_interface::return_type::ERROR; + RCLCPP_DEBUG(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Hardware interface not active"); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + return hardware_interface::return_type::OK; } if (!client_application_.client_app_read()) { - RCLCPP_ERROR(rclcpp::get_logger("ClientApplication"), "Failed to read data from controller"); + RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Failed to read data from controller"); return hardware_interface::return_type::ERROR; } @@ -186,9 +187,10 @@ hardware_interface::return_type KUKAFRIHardwareInterface::write( const rclcpp::Time &, const rclcpp::Duration &) { + // Write is called in inactive state, check is necessary if (!is_active_) { - RCLCPP_INFO(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Controller deactivated"); - return hardware_interface::return_type::ERROR; + RCLCPP_DEBUG(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Hardware interface not active"); + return hardware_interface::return_type::OK; } // Call the appropriate callback for the actual state (e.g. updateCommand) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index c5331d34..63e28de7 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -95,7 +95,6 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) std::dynamic_pointer_cast( this->shared_from_this()), robot_manager_); } - RCLCPP_INFO(get_logger(), "Successfully set 'controller_ip' parameter" ); // Start non-RT controllers @@ -165,7 +164,6 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) } // Cleanup hardware interface - // TODO(Svastits): interface cleanup is not called but result is success!! auto hw_request = std::make_shared(); hw_request->name = "iiwa_hardware"; From 1e08e04e7e2b892541d4c754179c6ecd19f76d09 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 19 Jul 2022 09:58:01 +0200 Subject: [PATCH 42/94] add controller name parameter --- .../include/kuka_sunrise/configuration_manager.hpp | 1 + .../src/kuka_sunrise/configuration_manager.cpp | 12 ++++++++++++ .../src/kuka_sunrise/kuka_fri_hardware_interface.cpp | 4 +++- .../src/kuka_sunrise/robot_manager_node.cpp | 11 +++++------ 4 files changed, 21 insertions(+), 7 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp index aa592de1..6585f771 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp @@ -61,6 +61,7 @@ class ConfigurationManager bool onSendPeriodChangeRequest(const int & send_period) const; bool onReceiveMultiplierChangeRequest(const int & receive_multiplier) const; bool onControllerIpChangeRequest(const std::string & controller_ip) const; + bool onControllerNameChangeRequest(const std::string & controller_name) const; bool setCommandMode(const std::string & control_mode) const; bool setReceiveMultiplier(int receive_multiplier) const; void setParameters(std_srvs::srv::Trigger::Response::SharedPtr response); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 258453b4..949961c1 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -197,6 +197,12 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr return true; } +bool ConfigurationManager::onControllerNameChangeRequest(const std::string & controller_name) const +{ + // TODO(Svastits): check available controller names + return true; +} + bool ConfigurationManager::setCommandMode(const std::string & control_mode) const { // TODO(Svastits): load and switch controllers through controller_manager @@ -282,6 +288,12 @@ void ConfigurationManager::setParameters(std_srvs::srv::Trigger::Response::Share return this->onJointDampingChangeRequest(joint_damping); }); + robot_manager_node_->registerParameter( + "controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, + true, false, true}, [this](const std::string & controller_name) { + return this->onControllerNameChangeRequest(controller_name); + }); + configured_ = true; response->success = true; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 4a1d3f06..3a6ee466 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -161,7 +161,9 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( } if (!client_application_.client_app_read()) { - RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Failed to read data from controller"); + RCLCPP_ERROR( + rclcpp::get_logger( + "KUKAFRIHardwareInterface"), "Failed to read data from controller"); return hardware_interface::return_type::ERROR; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 63e28de7..a7ab07cb 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -95,7 +95,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) std::dynamic_pointer_cast( this->shared_from_this()), robot_manager_); } - RCLCPP_INFO(get_logger(), "Successfully set 'controller_ip' parameter" ); + RCLCPP_INFO(get_logger(), "Successfully set 'controller_ip' parameter"); // Start non-RT controllers auto controller_request = @@ -254,11 +254,10 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } - // Activate forward_command_controller - // TODO(Svastits): add parameter for controller name + // Activate RT commander controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; controller_request->activate_controllers = - std::vector{"forward_command_controller_position"}; + std::vector{this->get_parameter("controller_name").as_string()}; controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); @@ -314,7 +313,8 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) std::make_shared(); controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; controller_request->deactivate_controllers = - std::vector{"joint_state_broadcaster", "forward_command_controller_position"}; + std::vector{"joint_state_broadcaster", + this->get_parameter("controller_name").as_string()}; auto controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); @@ -337,7 +337,6 @@ bool RobotManagerNode::activate() } if (!robot_manager_->activateControl()) { - // TODO(resizoltan) check robot control node state first this->ActivatableInterface::deactivate(); RCLCPP_ERROR(get_logger(), "Could not activate control"); return false; From b351d9db3f473120f6a2b488b81648e3119b5994 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 19 Jul 2022 11:08:34 +0200 Subject: [PATCH 43/94] add joint trajectory controller --- ...oller.yaml => forward_controller_config.yaml} | 2 +- .../config/iiwa_ros2_controller_config.yaml | 5 ++++- .../joint_trajectory_controller_config.yaml | 16 ++++++++++++++++ .../launch/kuka_sunrise_control.launch.py | 13 +++++++++++-- 4 files changed, 32 insertions(+), 4 deletions(-) rename kuka_sunrise_driver/config/{forward_controller.yaml => forward_controller_config.yaml} (85%) create mode 100644 kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml diff --git a/kuka_sunrise_driver/config/forward_controller.yaml b/kuka_sunrise_driver/config/forward_controller_config.yaml similarity index 85% rename from kuka_sunrise_driver/config/forward_controller.yaml rename to kuka_sunrise_driver/config/forward_controller_config.yaml index ad9e286c..8f514b3b 100644 --- a/kuka_sunrise_driver/config/forward_controller.yaml +++ b/kuka_sunrise_driver/config/forward_controller_config.yaml @@ -1,4 +1,4 @@ -/forward_command_controller_position: +/forward_command_controller: ros__parameters: joints: - LBRiiwa7Joint1 diff --git a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml index af5259a0..16d9471b 100755 --- a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml +++ b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml @@ -2,8 +2,11 @@ controller_manager: ros__parameters: update_rate: 100 # Hz - forward_command_controller_position: + forward_command_controller: type: forward_command_controller/ForwardCommandController + + joint_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster diff --git a/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml b/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml new file mode 100644 index 00000000..225d53cf --- /dev/null +++ b/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml @@ -0,0 +1,16 @@ +/joint_trajectory_controller: + ros__parameters: + joints: + - LBRiiwa7Joint1 + - LBRiiwa7Joint2 + - LBRiiwa7Joint3 + - LBRiiwa7Joint4 + - LBRiiwa7Joint5 + - LBRiiwa7Joint6 + - LBRiiwa7Joint7 + command_interfaces: + - position + state_interfaces: + - position + state_publish_rate: 50.0 + action_monitor_rate: 20.0 diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 7affecfa..36501020 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -33,7 +33,9 @@ def generate_launch_description(): controller_config = (get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml") forward_controller_config = (get_package_share_directory('kuka_sunrise') + - "/config/forward_controller.yaml") + "/config/forward_controller_config.yaml") + joint_traj_controller_cofig = (get_package_share_directory('kuka_sunrise') + + "/config/joint_trajectory_controller_config.yaml") robot_description_path = (get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/lbriiwa7.xacro") robot_description = {'robot_description': ParameterValue( @@ -49,6 +51,7 @@ def generate_launch_description(): LifecycleNode( namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', name=['robot_manager'], parameters=[{'controller_ip': ''}] + {'controller_name': 'joint_trajectory_controller'}] ), Node( package="controller_manager", @@ -58,9 +61,15 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["forward_command_controller_position", "-c", "/controller_manager", "-p", + arguments=["forward_command_controller", "-c", "/controller_manager", "-p", forward_controller_config, "--inactive"] ), + Node( + package="controller_manager", + executable="spawner", + arguments=["joint_trajectory_controller", "-c", "/controller_manager", "-p", + joint_traj_controller_cofig, "--inactive"] + ), Node( package="controller_manager", executable="spawner", From 3758f98d0c14fa90b567c1b80198e0a0ba5938f7 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 19 Jul 2022 11:21:10 +0200 Subject: [PATCH 44/94] remove setup.py, restruct config files --- kuka_sunrise_driver/CMakeLists.txt | 19 ---------- .../{params => config}/damping_params.yaml | 0 .../{params => config}/stiffness_params.yaml | 0 .../scripts/copyright/__init__.py | 0 .../__pycache__/__init__.cpython-36.pyc | Bin 156 -> 0 bytes .../__pycache__/copyright.cpython-36.pyc | Bin 188 -> 0 bytes .../scripts/copyright/copyright.py | 15 -------- kuka_sunrise_driver/setup.py | 35 ------------------ 8 files changed, 69 deletions(-) rename kuka_sunrise_driver/{params => config}/damping_params.yaml (100%) rename kuka_sunrise_driver/{params => config}/stiffness_params.yaml (100%) delete mode 100644 kuka_sunrise_driver/scripts/copyright/__init__.py delete mode 100644 kuka_sunrise_driver/scripts/copyright/__pycache__/__init__.cpython-36.pyc delete mode 100644 kuka_sunrise_driver/scripts/copyright/__pycache__/copyright.cpython-36.pyc delete mode 100644 kuka_sunrise_driver/scripts/copyright/copyright.py delete mode 100644 kuka_sunrise_driver/setup.py diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 492e9d43..67c4cf54 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -112,19 +112,6 @@ if(BUILD_TESTING) find_package(ament_cmake_uncrustify REQUIRED) find_package(ament_cmake_xmllint REQUIRED) - # install custom copyright name - install(CODE - "execute_process( - COMMAND - \"${PYTHON_EXECUTABLE}\" \"${PROJECT_SOURCE_DIR}/setup.py\" - \"egg_info\" \"--egg-base\" \"${PROJECT_BINARY_DIR}\" - \"build\" \"--build-base\" \"${PROJECT_BINARY_DIR}/build\" - \"install\" \"--prefix\" \"${CMAKE_INSTALL_PREFIX}\" - \"--record\" \"${PROJECT_BINARY_DIR}/install_copyright.log\" - \"--single-version-externally-managed\" - WORKING_DIRECTORY \"${PROJECT_SOURCE_DIR}\")" - ) - ament_copyright() ament_cppcheck(--language=c++) ament_pep257() @@ -162,9 +149,3 @@ if(TEST_COVERAGE) set_coverage_output_dir() endif() -if(TEST_COVERAGE) - # Define a coverage target with some libs and executables to check - # NAME Name of coverage target. Default: coverage. Only works with default currently. - # TARGETS Library and executable targets for which coverage reports are requested. - # add_coverage_gcov(NAME coverage TARGETS mypkg_lib mypkg_node) -endif() diff --git a/kuka_sunrise_driver/params/damping_params.yaml b/kuka_sunrise_driver/config/damping_params.yaml similarity index 100% rename from kuka_sunrise_driver/params/damping_params.yaml rename to kuka_sunrise_driver/config/damping_params.yaml diff --git a/kuka_sunrise_driver/params/stiffness_params.yaml b/kuka_sunrise_driver/config/stiffness_params.yaml similarity index 100% rename from kuka_sunrise_driver/params/stiffness_params.yaml rename to kuka_sunrise_driver/config/stiffness_params.yaml diff --git a/kuka_sunrise_driver/scripts/copyright/__init__.py b/kuka_sunrise_driver/scripts/copyright/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/kuka_sunrise_driver/scripts/copyright/__pycache__/__init__.cpython-36.pyc b/kuka_sunrise_driver/scripts/copyright/__pycache__/__init__.cpython-36.pyc deleted file mode 100644 index de87e0ee4f20661cd35bc7b4d67a161cc5769166..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 156 zcmXr!<>g`)v58{&=ek&P@K*9*(m#2P4er~FMQGRhs zYFTPdenDyxh+`CAUaVhSl&qg!nw=P5T$)#uS)8h0oLrPyP*SX)oL^8`l$oAUq8}fh dnU`4-AFo$Xd5gm)H$SB`C)EyQMKKUF006)MC;R{a diff --git a/kuka_sunrise_driver/scripts/copyright/__pycache__/copyright.cpython-36.pyc b/kuka_sunrise_driver/scripts/copyright/__pycache__/copyright.cpython-36.pyc deleted file mode 100644 index 5d215ea08fa2a6648075b6ebcb9d3f165839d598..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 188 zcmXr!<>mTiWfK?A#K7>F0SPby*$zNl%mE})7@`Y?8Nxu(!8R~;#B?OPO2S0$W=hh F0027sHWL5< diff --git a/kuka_sunrise_driver/scripts/copyright/copyright.py b/kuka_sunrise_driver/scripts/copyright/copyright.py deleted file mode 100644 index 24a59db4..00000000 --- a/kuka_sunrise_driver/scripts/copyright/copyright.py +++ /dev/null @@ -1,15 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -resizoltan = 'Zoltán Rési' diff --git a/kuka_sunrise_driver/setup.py b/kuka_sunrise_driver/setup.py deleted file mode 100644 index d3f6af9c..00000000 --- a/kuka_sunrise_driver/setup.py +++ /dev/null @@ -1,35 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from setuptools import find_packages, setup - - -setup( - name='kuka_sunrise', - package_dir={'': 'scripts'}, - version='0.0.1', - author='Zoltán Rési', - author_email='resizoltan@gmail.com', - description='Copyright entry point for ament_copyright linter', - classifiers=[ - 'Programming Language :: Python :: 3', - 'License :: OSI Approved :: Apache Software License' - ], - entry_points={ - 'ament_copyright.copyright_name': [ - 'resizoltan = copyright.copyright:resizoltan', - ], - }, - packages=find_packages('scripts'), -) From a2bbe1afc30ba43921ea91b27f4ef93148eb6f9e Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 19 Jul 2022 11:54:10 +0200 Subject: [PATCH 45/94] command mode switch skeleton --- .../kuka_fri_hardware_interface.hpp | 7 ++++++- .../kuka_fri_hardware_interface.cpp | 21 +++++++++++++++++++ 2 files changed, 27 insertions(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index b005649a..e084ac7a 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -70,7 +70,12 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, hardware_interface::return_type write( const rclcpp::Time & time, const rclcpp::Duration & period) override; - + hardware_interface::return_type prepare_command_mode_switch( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) override; + hardware_interface::return_type perform_command_mode_switch( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) override; void updateCommand(const rclcpp::Time & stamp); bool setReceiveMultiplier(int receive_multiplier); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 3a6ee466..a976f198 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -274,6 +274,27 @@ export_command_interfaces() } return command_interfaces; } + +hardware_interface::return_type KUKAFRIHardwareInterface::prepare_command_mode_switch( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) +{ + if (is_active_) { + RCLCPP_DEBUG( + rclcpp::get_logger( + "KUKAFRIHardwareInterface"), "Cannot change command mode if hardware interface is active"); + return hardware_interface::return_type::ERROR; + } else { + return hardware_interface::return_type::OK; + } +} + +hardware_interface::return_type KUKAFRIHardwareInterface::perform_command_mode_switch( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) +{ + return hardware_interface::return_type::OK; +} } // namespace kuka_sunrise PLUGINLIB_EXPORT_CLASS( From bcc86fc3ca2a60651d06c543aad89bfb9de109cf Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 27 Jul 2022 14:56:51 +0200 Subject: [PATCH 46/94] command mode switch --- .../config/forward_controller_config.yaml | 2 +- .../config/iiwa_ros2_controller_config.yaml | 9 +++--- .../joint_trajectory_controller_config.yaml | 2 +- .../kuka_fri_hardware_interface.hpp | 3 -- .../launch/kuka_sunrise_control.launch.py | 8 +---- .../kuka_sunrise/configuration_manager.cpp | 14 ++------- .../kuka_fri_hardware_interface.cpp | 29 ++++++++++++------- .../src/kuka_sunrise/robot_manager_node.cpp | 7 ++++- 8 files changed, 35 insertions(+), 39 deletions(-) diff --git a/kuka_sunrise_driver/config/forward_controller_config.yaml b/kuka_sunrise_driver/config/forward_controller_config.yaml index 8f514b3b..d8f99613 100644 --- a/kuka_sunrise_driver/config/forward_controller_config.yaml +++ b/kuka_sunrise_driver/config/forward_controller_config.yaml @@ -1,4 +1,4 @@ -/forward_command_controller: +/position_controller: # uniqe names will be available with HWIF parameter interface ros__parameters: joints: - LBRiiwa7Joint1 diff --git a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml index 16d9471b..fbd8a537 100755 --- a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml +++ b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml @@ -2,11 +2,12 @@ controller_manager: ros__parameters: update_rate: 100 # Hz - forward_command_controller: - type: forward_command_controller/ForwardCommandController - - joint_trajectory_controller: + position_controller: type: joint_trajectory_controller/JointTrajectoryController + # type: forward_command_controller/ForwardCommandController + + effort_controller: + type: effort_controllers/JointEffortController joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster diff --git a/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml b/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml index 225d53cf..af9fc401 100644 --- a/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml +++ b/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml @@ -1,4 +1,4 @@ -/joint_trajectory_controller: +/position_controller: # uniqe names will be available with HWIF parameter interface ros__parameters: joints: - LBRiiwa7Joint1 diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index e084ac7a..487dd24d 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -73,9 +73,6 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, hardware_interface::return_type prepare_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces) override; - hardware_interface::return_type perform_command_mode_switch( - const std::vector & start_interfaces, - const std::vector & stop_interfaces) override; void updateCommand(const rclcpp::Time & stamp); bool setReceiveMultiplier(int receive_multiplier); diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 36501020..d9cafd3e 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -61,13 +61,7 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["forward_command_controller", "-c", "/controller_manager", "-p", - forward_controller_config, "--inactive"] - ), - Node( - package="controller_manager", - executable="spawner", - arguments=["joint_trajectory_controller", "-c", "/controller_manager", "-p", + arguments=["position_controller", "-c", "/controller_manager", "-p", joint_traj_controller_cofig, "--inactive"] ), Node( diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 949961c1..d2ecdc00 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -197,12 +197,6 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr return true; } -bool ConfigurationManager::onControllerNameChangeRequest(const std::string & controller_name) const -{ - // TODO(Svastits): check available controller names - return true; -} - bool ConfigurationManager::setCommandMode(const std::string & control_mode) const { // TODO(Svastits): load and switch controllers through controller_manager @@ -288,12 +282,8 @@ void ConfigurationManager::setParameters(std_srvs::srv::Trigger::Response::Share return this->onJointDampingChangeRequest(joint_damping); }); - robot_manager_node_->registerParameter( - "controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, - true, false, true}, [this](const std::string & controller_name) { - return this->onControllerNameChangeRequest(controller_name); - }); - + // TODO(Svastits): add controller name parameters, when HWIF parameter interface is available + // currently syncing between manager node and HWIF is not possible, (only with ugly workaround) configured_ = true; response->success = true; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index a976f198..bcdf802b 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -131,6 +131,8 @@ CallbackReturn KUKAFRIHardwareInterface::on_deactivate(const rclcpp_lifecycle::S void KUKAFRIHardwareInterface::waitForCommand() { + hw_commands_ = hw_states_; + hw_effort_command_ = hw_torques_; // TODO(Svastits): is this really the purpose of waitForCommand? rclcpp::Time stamp = ros_clock_.now(); if (++receive_counter_ == receive_multiplier_) { @@ -279,20 +281,27 @@ hardware_interface::return_type KUKAFRIHardwareInterface::prepare_command_mode_s const std::vector & start_interfaces, const std::vector & stop_interfaces) { - if (is_active_) { - RCLCPP_DEBUG( + if (fri_state_ > 2) { + RCLCPP_ERROR( rclcpp::get_logger( - "KUKAFRIHardwareInterface"), "Cannot change command mode if hardware interface is active"); + "KUKAFRIHardwareInterface"), "Cannot change command mode if FRI is in commanding mode"); return hardware_interface::return_type::ERROR; - } else { - return hardware_interface::return_type::OK; + } else if (start_interfaces[0] == "position_controller" && + stop_interfaces[0] == "effort_controller") + { + RCLCPP_INFO( + rclcpp::get_logger( + "KUKAFRIHardwareInterface"), "Successfully changed to position command mode"); + torque_command_mode_ = false; + } else if (start_interfaces[0] == "effort_controller" && + stop_interfaces[0] == "position_controller") + { + RCLCPP_INFO( + rclcpp::get_logger( + "KUKAFRIHardwareInterface"), "Successfully changed to torque command mode"); + torque_command_mode_ = true; } -} -hardware_interface::return_type KUKAFRIHardwareInterface::perform_command_mode_switch( - const std::vector & start_interfaces, - const std::vector & stop_interfaces) -{ return hardware_interface::return_type::OK; } } // namespace kuka_sunrise diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index a7ab07cb..95a82e57 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -210,6 +210,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) RCLCPP_ERROR(get_logger(), "not connected"); return ERROR; } + auto send_period_ms = static_cast(this->get_parameter("send_period_ms").as_int()); auto receive_multiplier = static_cast(this->get_parameter("receive_multiplier").as_int()); if (!robot_manager_->setFRIConfig(30200, send_period_ms, receive_multiplier)) { @@ -257,7 +258,11 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) // Activate RT commander controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; controller_request->activate_controllers = - std::vector{this->get_parameter("controller_name").as_string()}; + std::vector{(this->get_parameter("command_mode").as_string() == + "position") ? "position_controller" : "effort_controller"}; + controller_request->deactivate_controllers = + std::vector{(this->get_parameter("command_mode").as_string() == + "position") ? "effort_controller" : "position_controller"}; controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); From 09973cd3038e190fb078473f749223bc28fe3e79 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 27 Jul 2022 15:31:48 +0200 Subject: [PATCH 47/94] add custom robot_state msg --- .../robot_state_broadcaster.hpp | 9 ++++--- .../src/robot_state_broadcaster.cpp | 24 +++++++------------ .../kuka_fri_hardware_interface.cpp | 3 +-- kuka_sunrise_interfaces/CMakeLists.txt | 10 +------- kuka_sunrise_interfaces/msg/RobotState.msg | 12 ++++++++++ 5 files changed, 27 insertions(+), 31 deletions(-) create mode 100644 kuka_sunrise_interfaces/msg/RobotState.msg diff --git a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp index 396749da..163d6556 100644 --- a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp +++ b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp @@ -22,7 +22,7 @@ #include "controller_interface/controller_interface.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" -#include "std_msgs/msg/int32.hpp" +#include "kuka_sunrise_interfaces/msg/robot_state.hpp" #include "rclcpp/time.hpp" #include "rclcpp/duration.hpp" @@ -54,10 +54,9 @@ class RobotStateBroadcaster : public controller_interface::ControllerInterface private: int fri_state_ = 0; int connection_quality_ = 0; - bool resend_state_ = true; - rclcpp::Publisher::SharedPtr fri_state_publisher_; - rclcpp::Publisher::SharedPtr connection_quality_publisher_; - std_msgs::msg::Int32 state_msg_; + int counter_ = 0; + rclcpp::Publisher::SharedPtr robot_state_publisher_; + kuka_sunrise_interfaces::msg::RobotState state_msg_; }; } // namespace kuka_controllers #endif // KUKA_CONTROLLERS__ROBOT_STATE_BROADCASTER_HPP_ diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp index fd3ffca8..be7c7090 100644 --- a/kuka_controllers/src/robot_state_broadcaster.cpp +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -19,10 +19,8 @@ namespace kuka_controllers controller_interface::CallbackReturn RobotStateBroadcaster::on_init() { // TODO(Svastits): choose appropriate QoS settings for late joiners - fri_state_publisher_ = get_node()->create_publisher( - "fri_state", rclcpp::SystemDefaultsQoS()); - connection_quality_publisher_ = get_node()->create_publisher( - "connection_quality", rclcpp::SystemDefaultsQoS()); + robot_state_publisher_ = get_node()->create_publisher( + "robot_state", rclcpp::SystemDefaultsQoS()); return controller_interface::CallbackReturn::SUCCESS; } @@ -66,19 +64,15 @@ controller_interface::return_type RobotStateBroadcaster::update( const rclcpp::Time &, const rclcpp::Duration &) { - // TODO(Svastits): create custom state msg type and publish all robot state info - // with given frequency -> measure additional system overload - state_msg_.data = state_interfaces_[0].get_value(); - if (fri_state_ != state_msg_.data) { - fri_state_ = state_msg_.data; - fri_state_publisher_->publish(state_msg_); - } + // TODO(Svastits): measure additional system overload, limit rate? + state_msg_.fri_state = state_interfaces_[0].get_value(); + state_msg_.connection_quality = state_interfaces_[1].get_value(); - state_msg_.data = state_interfaces_[1].get_value(); - if (connection_quality_ != state_msg_.data) { - connection_quality_ = state_msg_.data; - connection_quality_publisher_->publish(state_msg_); + if (counter_++ == 10) { + robot_state_publisher_->publish(state_msg_); + counter_ = 0; } + return controller_interface::return_type::OK; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index bcdf802b..4cdbdd06 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -212,8 +212,7 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) printf("client deactivated, exiting updateCommand\n"); return; } - // TODO(Svastits): implement command mode switch - if (torque_command_mode_) { + if (torque_command_mode_) { // TODO(Svastits): consider using robotState().getClientCommandMode() const double * joint_torques_ = hw_effort_command_.data(); robotCommand().setJointPosition(robotState().getIpoJointPosition()); robotCommand().setTorque(joint_torques_); diff --git a/kuka_sunrise_interfaces/CMakeLists.txt b/kuka_sunrise_interfaces/CMakeLists.txt index 084de4c1..a4dc3ebe 100644 --- a/kuka_sunrise_interfaces/CMakeLists.txt +++ b/kuka_sunrise_interfaces/CMakeLists.txt @@ -18,26 +18,18 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) -# uncomment the following section in order to fill in -# further dependencies manually. -# find_package( REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "srv/SetInt.srv" "srv/GetState.srv" "srv/SetDouble.srv" + "msg/RobotState.msg" ) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # uncomment the line when a copyright and license is not present in all source files - #set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # uncomment the line when this package is not in a git repo - #set(ament_cmake_cpplint_FOUND TRUE) ament_lint_auto_find_test_dependencies() endif() diff --git a/kuka_sunrise_interfaces/msg/RobotState.msg b/kuka_sunrise_interfaces/msg/RobotState.msg new file mode 100644 index 00000000..df6431f1 --- /dev/null +++ b/kuka_sunrise_interfaces/msg/RobotState.msg @@ -0,0 +1,12 @@ +# Message describing the state of the robot and FRI + +int32 fri_state +int32 connection_quality +int32 safety_state +int32 command_mode +int32 control_mode +int32 operation_mode +int32 drive_state +int32 session_state +int32 overlay_type +float64 tracking_performance From 8c1c327a36c8c381f0e6fa6d2e4be47248710293 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 27 Jul 2022 15:35:04 +0200 Subject: [PATCH 48/94] remove fri state from controller manager --- .../src/kuka_sunrise/sunrise_control_node.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 95190b0d..480b54d0 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -23,21 +23,14 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); - int fri_state = 0; auto executor = std::make_shared(); auto controller_manager = std::make_shared( executor, "controller_manager"); - std::thread control_loop([controller_manager, &fri_state]() { + std::thread control_loop([controller_manager]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); - auto callback = [&fri_state, controller_manager](std_msgs::msg::Int32::SharedPtr state) { - RCLCPP_INFO(controller_manager->get_logger(), "State received: %i", state->data); - fri_state = state->data; - }; - auto sub = - controller_manager->create_subscription("fri_state", 1, callback); while (rclcpp::ok()) { controller_manager->read(controller_manager->now(), dt); controller_manager->update(controller_manager->now(), dt); From 91a6fd357c7504e8456bf9ce8283fe9e603bc052 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 27 Jul 2022 17:00:15 +0200 Subject: [PATCH 49/94] shut down controller_manager from robot_manager --- .../src/kuka_sunrise/robot_manager_node.cpp | 21 ++++++++++++------- .../src/kuka_sunrise/sunrise_control_node.cpp | 11 +++++++++- 2 files changed, 23 insertions(+), 9 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 95a82e57..fab5e476 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -198,7 +198,12 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) return SUCCESS; } - // TODO(Svasits): unload controllers, destroy HWInterface + // Publish message to notify other nodes about shutdown + auto control_ended_pub = create_publisher("control_ended", rclcpp::QoS(1)); + std_msgs::msg::Bool end; + end.data = true; + control_ended_pub->publish(end); + return SUCCESS; } @@ -219,6 +224,13 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) } RCLCPP_INFO(get_logger(), "Successfully set FRI config"); + // Start FRI (in monitoring mode) + if (!robot_manager_->startFRI()) { + RCLCPP_ERROR(get_logger(), "Could not start FRI"); + return FAILURE; + } + RCLCPP_INFO(get_logger(), "Started FRI"); + // Activate hardware interface auto hw_request = std::make_shared(); @@ -233,13 +245,6 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) } RCLCPP_INFO(get_logger(), "Activated LBR iiwa hardware interface"); - // Start FRI (in monitoring mode) - if (!robot_manager_->startFRI()) { - RCLCPP_ERROR(get_logger(), "Could not start FRI"); - return FAILURE; - } - RCLCPP_INFO(get_logger(), "Started FRI"); - // Activate joint state broadcaster // The other controller must be started later so that it can initialize internal state // with broadcaster information diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 480b54d0..21e3bd54 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -17,7 +17,7 @@ #include "controller_manager/controller_manager.hpp" #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/int32.hpp" +#include "std_msgs/msg/bool.hpp" int main(int argc, char ** argv) { @@ -27,6 +27,15 @@ int main(int argc, char ** argv) auto controller_manager = std::make_shared( executor, "controller_manager"); + + auto callback = [controller_manager](std_msgs::msg::Bool::SharedPtr state) { + RCLCPP_INFO(controller_manager->get_logger(), "Robot manager node shut down, terminating"); + rclcpp::shutdown(); + }; + auto sub = + controller_manager->create_subscription("control_ended", 1, callback); + + std::thread control_loop([controller_manager]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); From 61e985be1d484203c9c1a8f38c3cf5f5ac80e414 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 27 Jul 2022 17:10:50 +0200 Subject: [PATCH 50/94] comments, uncrustify --- .../src/kuka_sunrise/kuka_fri_hardware_interface.cpp | 1 + .../src/kuka_sunrise/robot_manager_node.cpp | 7 ++++--- .../src/kuka_sunrise/sunrise_control_node.cpp | 8 ++++---- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 4cdbdd06..074e0efc 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -180,6 +180,7 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( tracking_performance_ = robotState().getTrackingPerformance(); fri_state_ = robotState().getSessionState(); connection_quality_ = robotState().getConnectionQuality(); + // TODO(Svastits): get states, create interfaces for (size_t i = 0; i < gpio_outputs_.size(); ++i) { gpio_outputs_[i].getValue(); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index fab5e476..89e25407 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -219,7 +219,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) auto send_period_ms = static_cast(this->get_parameter("send_period_ms").as_int()); auto receive_multiplier = static_cast(this->get_parameter("receive_multiplier").as_int()); if (!robot_manager_->setFRIConfig(30200, send_period_ms, receive_multiplier)) { - RCLCPP_ERROR(get_logger(), "could not set fri config"); + RCLCPP_ERROR(get_logger(), "could not set FRI config"); return FAILURE; } RCLCPP_INFO(get_logger(), "Successfully set FRI config"); @@ -267,7 +267,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) "position") ? "position_controller" : "effort_controller"}; controller_request->deactivate_controllers = std::vector{(this->get_parameter("command_mode").as_string() == - "position") ? "effort_controller" : "position_controller"}; + "position") ? "effort_controller" : "position_controller"}; // TODO(Svastits): remove if unnecessary controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); @@ -324,7 +324,8 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; controller_request->deactivate_controllers = std::vector{"joint_state_broadcaster", - this->get_parameter("controller_name").as_string()}; + (this->get_parameter("command_mode").as_string() == + "position") ? "effort_controller" : "position_controller"}; auto controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 21e3bd54..53e1f7fe 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -29,11 +29,11 @@ int main(int argc, char ** argv) "controller_manager"); auto callback = [controller_manager](std_msgs::msg::Bool::SharedPtr state) { - RCLCPP_INFO(controller_manager->get_logger(), "Robot manager node shut down, terminating"); - rclcpp::shutdown(); - }; + RCLCPP_INFO(controller_manager->get_logger(), "Robot manager node shut down, terminating"); + rclcpp::shutdown(); + }; auto sub = - controller_manager->create_subscription("control_ended", 1, callback); + controller_manager->create_subscription("control_ended", 1, callback); std::thread control_loop([controller_manager]() { From 42e10ec9baa3e9dce5ef1a5d02b62e0f5dbb3104 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 09:08:13 +0200 Subject: [PATCH 51/94] rework command mode change --- .../kuka_fri_hardware_interface.hpp | 5 +-- .../kuka_fri_hardware_interface.cpp | 38 ++++--------------- .../src/kuka_sunrise/robot_manager_node.cpp | 7 +--- 3 files changed, 11 insertions(+), 39 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 487dd24d..52d6b76f 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -31,6 +31,8 @@ #include "fri/friLBRClient.h" #include "fri/HWIFClientApplication.hpp" #include "fri/friUdpConnection.h" +#include "fri/friClientIf.h" + #include "pluginlib/class_list_macros.hpp" @@ -70,9 +72,6 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, hardware_interface::return_type write( const rclcpp::Time & time, const rclcpp::Duration & period) override; - hardware_interface::return_type prepare_command_mode_switch( - const std::vector & start_interfaces, - const std::vector & stop_interfaces) override; void updateCommand(const rclcpp::Time & stamp); bool setReceiveMultiplier(int receive_multiplier); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 074e0efc..27193af3 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -210,17 +210,21 @@ hardware_interface::return_type KUKAFRIHardwareInterface::write( void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) { if (!is_active_) { - printf("client deactivated, exiting updateCommand\n"); + RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Hardware inactive, exiting updateCommand"); return; } - if (torque_command_mode_) { // TODO(Svastits): consider using robotState().getClientCommandMode() + if (command_mode_ == KUKA::FRI::EClientCommandMode::TORQUE) { const double * joint_torques_ = hw_effort_command_.data(); robotCommand().setJointPosition(robotState().getIpoJointPosition()); robotCommand().setTorque(joint_torques_); - } else { + } else if (command_mode_ == KUKA::FRI::EClientCommandMode::POSITION) { const double * joint_positions_ = hw_commands_.data(); robotCommand().setJointPosition(joint_positions_); } + else + { + RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Unsupported command mode"); + } for (size_t i = 0; i < gpio_inputs_.size(); ++i) { gpio_inputs_[i].setValue(); @@ -276,34 +280,6 @@ export_command_interfaces() } return command_interfaces; } - -hardware_interface::return_type KUKAFRIHardwareInterface::prepare_command_mode_switch( - const std::vector & start_interfaces, - const std::vector & stop_interfaces) -{ - if (fri_state_ > 2) { - RCLCPP_ERROR( - rclcpp::get_logger( - "KUKAFRIHardwareInterface"), "Cannot change command mode if FRI is in commanding mode"); - return hardware_interface::return_type::ERROR; - } else if (start_interfaces[0] == "position_controller" && - stop_interfaces[0] == "effort_controller") - { - RCLCPP_INFO( - rclcpp::get_logger( - "KUKAFRIHardwareInterface"), "Successfully changed to position command mode"); - torque_command_mode_ = false; - } else if (start_interfaces[0] == "effort_controller" && - stop_interfaces[0] == "position_controller") - { - RCLCPP_INFO( - rclcpp::get_logger( - "KUKAFRIHardwareInterface"), "Successfully changed to torque command mode"); - torque_command_mode_ = true; - } - - return hardware_interface::return_type::OK; -} } // namespace kuka_sunrise PLUGINLIB_EXPORT_CLASS( diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 89e25407..9184c2fb 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -264,10 +264,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; controller_request->activate_controllers = std::vector{(this->get_parameter("command_mode").as_string() == - "position") ? "position_controller" : "effort_controller"}; - controller_request->deactivate_controllers = - std::vector{(this->get_parameter("command_mode").as_string() == - "position") ? "effort_controller" : "position_controller"}; // TODO(Svastits): remove if unnecessary + "position") ? "position_controller" : "effort_controller"}; // TODO(Svastits): use parameter controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); @@ -325,7 +322,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) controller_request->deactivate_controllers = std::vector{"joint_state_broadcaster", (this->get_parameter("command_mode").as_string() == - "position") ? "effort_controller" : "position_controller"}; + "position") ? "effort_controller" : "position_controller"}; // TODO(Svastits): use parameter auto controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); From b320514bf8374fef6d6b04c080f7b147af4e9fbe Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 09:17:04 +0200 Subject: [PATCH 52/94] publish robot state (with reduced rate) --- .../robot_state_broadcaster.hpp | 2 +- .../kuka_controllers/timing_controller.hpp | 2 +- .../src/robot_state_broadcaster.cpp | 21 +++++++++++++++---- kuka_controllers/src/timing_controller.cpp | 2 +- .../kuka_fri_hardware_interface.hpp | 10 ++++++++- .../kuka_fri_hardware_interface.cpp | 19 +++++++++++++---- kuka_sunrise_interfaces/msg/RobotState.msg | 3 +-- 7 files changed, 45 insertions(+), 14 deletions(-) diff --git a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp index 163d6556..429268de 100644 --- a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp +++ b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp @@ -10,7 +10,7 @@ // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and -// limitations under the License.------------------------------------------------------------------- +// limitations under the License. #ifndef KUKA_CONTROLLERS__ROBOT_STATE_BROADCASTER_HPP_ diff --git a/kuka_controllers/include/kuka_controllers/timing_controller.hpp b/kuka_controllers/include/kuka_controllers/timing_controller.hpp index 4fc62d5a..3d17339b 100644 --- a/kuka_controllers/include/kuka_controllers/timing_controller.hpp +++ b/kuka_controllers/include/kuka_controllers/timing_controller.hpp @@ -10,7 +10,7 @@ // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and -// limitations under the License.------------------------------------------------------------------- +// limitations under the License. #ifndef KUKA_CONTROLLERS__TIMING_CONTROLLER_HPP_ diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp index be7c7090..d28cb35f 100644 --- a/kuka_controllers/src/robot_state_broadcaster.cpp +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -10,7 +10,7 @@ // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and -// limitations under the License.------------------------------------------------------------------- +// limitations under the License. #include "kuka_controllers/robot_state_broadcaster.hpp" @@ -18,7 +18,6 @@ namespace kuka_controllers { controller_interface::CallbackReturn RobotStateBroadcaster::on_init() { - // TODO(Svastits): choose appropriate QoS settings for late joiners robot_state_publisher_ = get_node()->create_publisher( "robot_state", rclcpp::SystemDefaultsQoS()); return controller_interface::CallbackReturn::SUCCESS; @@ -37,8 +36,15 @@ const { controller_interface::InterfaceConfiguration config; config.type = controller_interface::interface_configuration_type::INDIVIDUAL; - config.names.push_back("state/fri_state"); + config.names.push_back("state/session_state"); config.names.push_back("state/connection_quality"); + config.names.push_back("state/safety_state"); + config.names.push_back("state/command_mode"); + config.names.push_back("state/control_mode"); + config.names.push_back("state/operation_mode"); + config.names.push_back("state/drive_state"); + config.names.push_back("state/overlay_type"); + config.names.push_back("state/tracking_performance"); return config; } @@ -65,8 +71,15 @@ controller_interface::return_type RobotStateBroadcaster::update( const rclcpp::Duration &) { // TODO(Svastits): measure additional system overload, limit rate? - state_msg_.fri_state = state_interfaces_[0].get_value(); + state_msg_.session_state = state_interfaces_[0].get_value(); state_msg_.connection_quality = state_interfaces_[1].get_value(); + state_msg_.safety_state = state_interfaces_[2].get_value(); + state_msg_.command_mode = state_interfaces_[3].get_value(); + state_msg_.control_mode = state_interfaces_[4].get_value(); + state_msg_.operation_mode = state_interfaces_[5].get_value(); + state_msg_.drive_state = state_interfaces_[6].get_value(); + state_msg_.overlay_type = state_interfaces_[7].get_value(); + state_msg_.tracking_performance = state_interfaces_[8].get_value(); if (counter_++ == 10) { robot_state_publisher_->publish(state_msg_); diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp index f38fc22f..a3ce5dc4 100644 --- a/kuka_controllers/src/timing_controller.cpp +++ b/kuka_controllers/src/timing_controller.cpp @@ -10,7 +10,7 @@ // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and -// limitations under the License.------------------------------------------------------------------- +// limitations under the License. #include "kuka_controllers/timing_controller.hpp" diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 52d6b76f..a612a5a2 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -98,8 +98,16 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, std::vector hw_torques_; std::vector hw_effort_command_; double tracking_performance_ = 1; - double fri_state_ = 0; + + // Enum values represented with doubles (as all interfaces must be pointers to doubles) + double session_state_ = 0; double connection_quality_ = 0; + double command_mode_ = 0; + double safety_state_ = 0; + double control_mode_ = 0; + double operation_mode_ = 0; + double drive_state_ = 0; + double overlay_type_ = 0; IOTypes getType(const std::string type_string) { diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 27193af3..8e6c13d1 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -178,9 +178,14 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( hw_torques_ext_.assign(external_torque, external_torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); tracking_performance_ = robotState().getTrackingPerformance(); - fri_state_ = robotState().getSessionState(); + session_state_ = robotState().getSessionState(); connection_quality_ = robotState().getConnectionQuality(); - // TODO(Svastits): get states, create interfaces + command_mode_ = robotState().getClientCommandMode(); + safety_state_ = robotState().getSafetyState(); + control_mode_ = robotState().getControlMode(); + operation_mode_ = robotState().getOperationMode(); + drive_state_ = robotState().getDriveState(); + overlay_type_ = robotState().getOverlayType(); for (size_t i = 0; i < gpio_outputs_.size(); ++i) { gpio_outputs_[i].getValue(); @@ -235,9 +240,15 @@ std::vector KUKAFRIHardwareInterface::export { std::vector state_interfaces; - state_interfaces.emplace_back("state", "fri_state", &fri_state_); + state_interfaces.emplace_back("state", "session_state", &session_state_); state_interfaces.emplace_back("state", "connection_quality", &connection_quality_); - + state_interfaces.emplace_back("state", "safety_state", &safety_state_); + state_interfaces.emplace_back("state", "command_mode", &command_mode_); + state_interfaces.emplace_back("state", "control_mode", &control_mode_); + state_interfaces.emplace_back("state", "operation_mode", &operation_mode_); + state_interfaces.emplace_back("state", "drive_state", &drive_state_); + state_interfaces.emplace_back("state", "overlay_type", &overlay_type_); + state_interfaces.emplace_back("state", "tracking_performance", &tracking_performance_); // Register I/O outputs (read access) and inputs (write access) for (size_t i = 0; i < gpio_outputs_.size(); ++i) { diff --git a/kuka_sunrise_interfaces/msg/RobotState.msg b/kuka_sunrise_interfaces/msg/RobotState.msg index df6431f1..2ed08e18 100644 --- a/kuka_sunrise_interfaces/msg/RobotState.msg +++ b/kuka_sunrise_interfaces/msg/RobotState.msg @@ -1,12 +1,11 @@ # Message describing the state of the robot and FRI -int32 fri_state +int32 session_state int32 connection_quality int32 safety_state int32 command_mode int32 control_mode int32 operation_mode int32 drive_state -int32 session_state int32 overlay_type float64 tracking_performance From d75dd81444e3605612caf6eafb1890a1bd35f377 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 10:03:46 +0200 Subject: [PATCH 53/94] add controller name parameters --- kuka_sunrise_driver/CMakeLists.txt | 2 +- .../kuka_sunrise/configuration_manager.hpp | 2 + .../kuka_sunrise/robot_manager_node.hpp | 2 + .../kuka_sunrise/configuration_manager.cpp | 42 +++++++++++++++++-- .../kuka_fri_hardware_interface.cpp | 10 ++--- .../src/kuka_sunrise/robot_manager_node.cpp | 18 ++++---- 6 files changed, 55 insertions(+), 21 deletions(-) diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 67c4cf54..95988f50 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -56,7 +56,7 @@ target_link_libraries(kuka_fri_hw_interface fri::fri_client) add_library(configuration_manager SHARED src/kuka_sunrise/configuration_manager.cpp) -ament_target_dependencies(configuration_manager kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core) +ament_target_dependencies(configuration_manager kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core controller_manager_msgs) add_executable(robot_manager_node diff --git a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp index 6585f771..4852cf6f 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp @@ -26,6 +26,7 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" #include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "controller_manager_msgs/srv/list_controllers.hpp" #include "kroshu_ros2_core/ROS2BaseLCNode.hpp" @@ -49,6 +50,7 @@ class ConfigurationManager rclcpp::CallbackGroup::SharedPtr param_cbg_; rclcpp::Client::SharedPtr command_mode_client_; rclcpp::Client::SharedPtr receive_multiplier_client_; + rclcpp::Client::SharedPtr get_controllers_client_; rclcpp::Service::SharedPtr set_parameter_service_; std::vector joint_stiffness_ = std::vector(7, 1000.0); diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index 705c1f27..8cb31428 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -31,6 +31,7 @@ #include "kuka_sunrise/robot_manager.hpp" #include "kuka_sunrise/configuration_manager.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" +#include "kuka_sunrise/internal/service_tools.hpp" #include "kroshu_ros2_core/ROS2BaseLCNode.hpp" @@ -74,6 +75,7 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat rclcpp::Service::SharedPtr change_robot_commanding_state_service_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr command_state_changed_publisher_; + std::string controller_name_; bool requestRobotControlNodeStateTransition(std::uint8_t transition); bool setRobotControlNodeCommandState(bool active); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index d2ecdc00..1929b03c 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -52,6 +52,10 @@ ConfigurationManager::ConfigurationManager( std_srvs::srv::Trigger::Response::SharedPtr response) { this->setParameters(response); }, ::rmw_qos_profile_default, param_cbg_); + + get_controllers_client_ = + robot_manager_node->create_client( + "controller_manager/list_controllers", qos.get_rmw_qos_profile(), cbg_); } bool ConfigurationManager::onCommandModeChangeRequest(const std::string & command_mode) const @@ -180,7 +184,7 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr split_ip.push_back(controller_ip.substr(i, controller_ip.length())); if (split_ip.size() != 4) { - RCLCPP_ERROR(robot_manager_node_->get_logger(), "Valid ip must have 3 '.' delimiters"); + RCLCPP_ERROR(robot_manager_node_->get_logger(), "Valid IP must have 3 '.' delimiters"); return false; } @@ -197,9 +201,29 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr return true; } +bool ConfigurationManager::onControllerNameChangeRequest(const std::string & controller_name) const +{ + auto request = std::make_shared(); + auto response = + kuka_sunrise::sendRequest( + get_controllers_client_, request, 0, 1000); + + if (!response) { + RCLCPP_ERROR(robot_manager_node_->get_logger(), "Could not get controller names"); + return false; + } + + for (auto controller: response->controller) { + if (controller_name == controller.name) {return true;} + } + RCLCPP_ERROR( + robot_manager_node_->get_logger(), "Controller name %s not available", + controller_name.c_str()); + return false; +} + bool ConfigurationManager::setCommandMode(const std::string & control_mode) const { - // TODO(Svastits): load and switch controllers through controller_manager ClientCommandModeID client_command_mode; if (control_mode == "position") { client_command_mode = POSITION_COMMAND_MODE; @@ -282,8 +306,18 @@ void ConfigurationManager::setParameters(std_srvs::srv::Trigger::Response::Share return this->onJointDampingChangeRequest(joint_damping); }); - // TODO(Svastits): add controller name parameters, when HWIF parameter interface is available - // currently syncing between manager node and HWIF is not possible, (only with ugly workaround) + robot_manager_node_->registerParameter( + "position_controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, + false, false, true}, [this](const std::string & controller_name) { + return this->onControllerNameChangeRequest(controller_name); + }); + + robot_manager_node_->registerParameter( + "torque_controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, + false, false, true}, [this](const std::string & controller_name) { + return this->onControllerNameChangeRequest(controller_name); + }); + configured_ = true; response->success = true; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 8e6c13d1..34026a58 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -215,7 +215,9 @@ hardware_interface::return_type KUKAFRIHardwareInterface::write( void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) { if (!is_active_) { - RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Hardware inactive, exiting updateCommand"); + RCLCPP_ERROR( + rclcpp::get_logger( + "KUKAFRIHardwareInterface"), "Hardware inactive, exiting updateCommand"); return; } if (command_mode_ == KUKA::FRI::EClientCommandMode::TORQUE) { @@ -225,10 +227,8 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) } else if (command_mode_ == KUKA::FRI::EClientCommandMode::POSITION) { const double * joint_positions_ = hw_commands_.data(); robotCommand().setJointPosition(joint_positions_); - } - else - { - RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Unsupported command mode"); + } else { + RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Unsupported command mode"); } for (size_t i = 0; i < gpio_inputs_.size(); ++i) { diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 9184c2fb..72aba961 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -14,10 +14,7 @@ #include -#include "std_msgs/msg/bool.hpp" - #include "kuka_sunrise/robot_manager_node.hpp" -#include "kuka_sunrise/internal/service_tools.hpp" namespace kuka_sunrise { @@ -260,11 +257,14 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } + + auto position_controller_name = this->get_parameter("position_controller_name").as_string(); + auto torque_controller_name = this->get_parameter("torque_controller_name").as_string(); + controller_name_ = (this->get_parameter("command_mode").as_string() == + "position") ? position_controller_name : torque_controller_name; // Activate RT commander controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->activate_controllers = - std::vector{(this->get_parameter("command_mode").as_string() == - "position") ? "position_controller" : "effort_controller"}; // TODO(Svastits): use parameter + controller_request->activate_controllers = std::vector{controller_name_}; controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); @@ -314,15 +314,11 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) } RCLCPP_INFO(get_logger(), "Deactivated LBR iiwa hardware interface"); - // Stop RT controllers auto controller_request = std::make_shared(); controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; - controller_request->deactivate_controllers = - std::vector{"joint_state_broadcaster", - (this->get_parameter("command_mode").as_string() == - "position") ? "effort_controller" : "position_controller"}; // TODO(Svastits): use parameter + controller_request->deactivate_controllers = std::vector{controller_name_}; auto controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); From c5a8b970e78bb0edbcca59e3f04e439b97e728c8 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 11:35:47 +0200 Subject: [PATCH 54/94] update launch file --- kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py | 3 ++- kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index d9cafd3e..c31323dd 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -51,7 +51,8 @@ def generate_launch_description(): LifecycleNode( namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', name=['robot_manager'], parameters=[{'controller_ip': ''}] - {'controller_name': 'joint_trajectory_controller'}] + {'position_controller_name': 'position_controller'}, + {'torque_controller_name': 'position_controller'}] ), Node( package="controller_manager", diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 72aba961..3c2b2bcf 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -253,7 +253,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); if (!controller_response || !controller_response->ok) { - RCLCPP_ERROR(get_logger(), "Could not start controllers"); + RCLCPP_ERROR(get_logger(), "Could not start joint state broadcaster"); return FAILURE; } From ecd9f77692995f05f4cf8cd2e26d777fab8833e2 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 11:38:23 +0200 Subject: [PATCH 55/94] launch file syntax fix --- kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index c31323dd..b8bdeaea 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -50,7 +50,7 @@ def generate_launch_description(): ), LifecycleNode( namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', - name=['robot_manager'], parameters=[{'controller_ip': ''}] + name=['robot_manager'], parameters=[{'controller_ip': ''}, {'position_controller_name': 'position_controller'}, {'torque_controller_name': 'position_controller'}] ), From f6da6e87ee53e8f92473e98ea687d7bb8ac9aa0d Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 12:36:53 +0200 Subject: [PATCH 56/94] check available controllers in command mode change --- .../kuka_sunrise/configuration_manager.hpp | 10 ++- .../kuka_sunrise/configuration_manager.cpp | 79 +++++++++++-------- .../src/kuka_sunrise/sunrise_control_node.cpp | 2 +- 3 files changed, 57 insertions(+), 34 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp index 4852cf6f..7a10e12d 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp @@ -44,11 +44,12 @@ class ConfigurationManager private: bool configured_ = false; + bool position_controller_available_ = false; + bool torque_controller_available_ = false; std::shared_ptr robot_manager_node_; std::shared_ptr robot_manager_; rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp::CallbackGroup::SharedPtr param_cbg_; - rclcpp::Client::SharedPtr command_mode_client_; rclcpp::Client::SharedPtr receive_multiplier_client_; rclcpp::Client::SharedPtr get_controllers_client_; rclcpp::Service::SharedPtr set_parameter_service_; @@ -56,6 +57,11 @@ class ConfigurationManager std::vector joint_stiffness_ = std::vector(7, 1000.0); std::vector joint_damping_ = std::vector(7, 0.7); + const std::string POSITION_COMMAND = "position"; + const std::string TORQUE_COMMAND = "torque"; + const std::string POSITION_CONTROL = "position"; + const std::string IMPEDANCE_CONTROL = "joint_impedance"; + bool onCommandModeChangeRequest(const std::string & command_mode) const; bool onControlModeChangeRequest(const std::string & control_mode) const; bool onJointStiffnessChangeRequest(const std::vector & joint_stiffness); @@ -63,7 +69,7 @@ class ConfigurationManager bool onSendPeriodChangeRequest(const int & send_period) const; bool onReceiveMultiplierChangeRequest(const int & receive_multiplier) const; bool onControllerIpChangeRequest(const std::string & controller_ip) const; - bool onControllerNameChangeRequest(const std::string & controller_name) const; + bool onControllerNameChangeRequest(const std::string & controller_name, bool position); bool setCommandMode(const std::string & control_mode) const; bool setReceiveMultiplier(int receive_multiplier) const; void setParameters(std_srvs::srv::Trigger::Response::SharedPtr response); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 1929b03c..788fbf78 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -33,8 +33,6 @@ ConfigurationManager::ConfigurationManager( rclcpp::CallbackGroupType::MutuallyExclusive); param_cbg_ = robot_manager_node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); - command_mode_client_ = robot_manager_node->create_client( - "set_command_mode", qos.get_rmw_qos_profile(), cbg_); receive_multiplier_client_ = robot_manager_node->create_client< kuka_sunrise_interfaces::srv::SetInt>( "set_receive_multiplier", qos.get_rmw_qos_profile(), @@ -60,12 +58,12 @@ ConfigurationManager::ConfigurationManager( bool ConfigurationManager::onCommandModeChangeRequest(const std::string & command_mode) const { - if (command_mode == "position") { - if (!setCommandMode("position")) { + if (command_mode == POSITION_COMMAND) { + if (!position_controller_available_ || !setCommandMode(POSITION_COMMAND)) { return false; } - } else if (command_mode == "torque") { - if (robot_manager_node_->get_parameter("control_mode").as_string() != "joint_impedance") { + } else if (command_mode == TORQUE_COMMAND) { + if (robot_manager_node_->get_parameter("control_mode").as_string() != IMPEDANCE_CONTROL) { RCLCPP_ERROR( robot_manager_node_->get_logger(), "Unable to set torque command mode, if control mode is not 'joint impedance'"); @@ -77,12 +75,13 @@ bool ConfigurationManager::onCommandModeChangeRequest(const std::string & comman "Unable to set torque command mode, if send period is bigger than 5 [ms]"); return false; } - if (!setCommandMode("torque")) { + if (!torque_controller_available_ || !setCommandMode(TORQUE_COMMAND)) { return false; } } else { RCLCPP_ERROR( - robot_manager_node_->get_logger(), "Command mode should be 'position' or 'torque'"); + robot_manager_node_->get_logger(), "Command mode should be '%s' or '%s'", + POSITION_COMMAND.c_str(), TORQUE_COMMAND.c_str()); return false; } RCLCPP_INFO(robot_manager_node_->get_logger(), "Successfully set command mode"); @@ -91,9 +90,9 @@ bool ConfigurationManager::onCommandModeChangeRequest(const std::string & comman bool ConfigurationManager::onControlModeChangeRequest(const std::string & control_mode) const { - if (control_mode == "position") { + if (control_mode == POSITION_CONTROL) { return robot_manager_->setPositionControlMode(); - } else if (control_mode == "joint_impedance") { + } else if (control_mode == IMPEDANCE_CONTROL) { try { return robot_manager_->setJointImpedanceControlMode( joint_stiffness_, @@ -104,7 +103,8 @@ bool ConfigurationManager::onControlModeChangeRequest(const std::string & contro return false; } else { RCLCPP_ERROR( - robot_manager_node_->get_logger(), "Control mode should be 'position' or 'joint_impedance'"); + robot_manager_node_->get_logger(), "Control mode should be '%s' or '%s'", + POSITION_CONTROL.c_str(), IMPEDANCE_CONTROL.c_str()); return false; } } @@ -201,7 +201,9 @@ bool ConfigurationManager::onControllerIpChangeRequest(const std::string & contr return true; } -bool ConfigurationManager::onControllerNameChangeRequest(const std::string & controller_name) const +bool ConfigurationManager::onControllerNameChangeRequest( + const std::string & controller_name, + bool position) { auto request = std::make_shared(); auto response = @@ -213,21 +215,36 @@ bool ConfigurationManager::onControllerNameChangeRequest(const std::string & con return false; } + if (controller_name == "") { + RCLCPP_WARN( + robot_manager_node_->get_logger(), "Controller for %s command mode not available", + position ? POSITION_COMMAND.c_str() : TORQUE_COMMAND.c_str()); + if (position) {position_controller_available_ = false;} else { + torque_controller_available_ = false; + } + return true; + } + for (auto controller: response->controller) { - if (controller_name == controller.name) {return true;} + if (controller_name == controller.name) { + if (position) {position_controller_available_ = true;} else { + torque_controller_available_ = true; + } + return true; + } } RCLCPP_ERROR( - robot_manager_node_->get_logger(), "Controller name %s not available", + robot_manager_node_->get_logger(), "Controller name '%s' not available", controller_name.c_str()); return false; } -bool ConfigurationManager::setCommandMode(const std::string & control_mode) const +bool ConfigurationManager::setCommandMode(const std::string & command_mode) const { ClientCommandModeID client_command_mode; - if (control_mode == "position") { + if (command_mode == POSITION_COMMAND) { client_command_mode = POSITION_COMMAND_MODE; - } else if (control_mode == "torque") { + } else if (command_mode == TORQUE_COMMAND) { client_command_mode = TORQUE_COMMAND_MODE; } else { RCLCPP_ERROR(robot_manager_node_->get_logger(), "Invalid control mode"); @@ -270,13 +287,25 @@ void ConfigurationManager::setParameters(std_srvs::srv::Trigger::Response::Share // parameter type (or value), the nodes must be launched again with changed parameters // because they could not be declared, therefore change is not possible in runtime robot_manager_node_->registerParameter( - "control_mode", "position", kroshu_ros2_core::ParameterSetAccessRights {false, true, true, + "control_mode", POSITION_CONTROL, kroshu_ros2_core::ParameterSetAccessRights {false, true, true, false, true}, [this](const std::string & control_mode) { return this->onControlModeChangeRequest(control_mode); }); robot_manager_node_->registerParameter( - "command_mode", "position", kroshu_ros2_core::ParameterSetAccessRights {false, true, true, + "position_controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, + false, false, true}, [this](const std::string & controller_name) { + return this->onControllerNameChangeRequest(controller_name, true); + }); + + robot_manager_node_->registerParameter( + "torque_controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, + false, false, true}, [this](const std::string & controller_name) { + return this->onControllerNameChangeRequest(controller_name, false); + }); + + robot_manager_node_->registerParameter( + "command_mode", POSITION_COMMAND, kroshu_ros2_core::ParameterSetAccessRights {false, true, true, false, true}, [this](const std::string & command_mode) { return this->onCommandModeChangeRequest(command_mode); }); @@ -306,18 +335,6 @@ void ConfigurationManager::setParameters(std_srvs::srv::Trigger::Response::Share return this->onJointDampingChangeRequest(joint_damping); }); - robot_manager_node_->registerParameter( - "position_controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, - false, false, true}, [this](const std::string & controller_name) { - return this->onControllerNameChangeRequest(controller_name); - }); - - robot_manager_node_->registerParameter( - "torque_controller_name", "", kroshu_ros2_core::ParameterSetAccessRights {false, true, - false, false, true}, [this](const std::string & controller_name) { - return this->onControllerNameChangeRequest(controller_name); - }); - configured_ = true; response->success = true; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 53e1f7fe..52d8153c 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -28,7 +28,7 @@ int main(int argc, char ** argv) executor, "controller_manager"); - auto callback = [controller_manager](std_msgs::msg::Bool::SharedPtr state) { + auto callback = [controller_manager](std_msgs::msg::Bool::SharedPtr) { RCLCPP_INFO(controller_manager->get_logger(), "Robot manager node shut down, terminating"); rclcpp::shutdown(); }; From d02e09f70a6e2430136eb700b2b2f3890e7bc016 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 12:49:37 +0200 Subject: [PATCH 57/94] lint, change controller names --- kuka_sunrise_driver/CMakeLists.txt | 3 ++- .../config/forward_controller_config.yaml | 2 +- .../config/iiwa_ros2_controller_config.yaml | 3 +-- .../config/joint_trajectory_controller_config.yaml | 2 +- .../include/kuka_sunrise/robot_manager_node.hpp | 1 + .../launch/kuka_sunrise_control.launch.py | 13 +++++++------ .../src/kuka_sunrise/configuration_manager.cpp | 2 +- 7 files changed, 14 insertions(+), 12 deletions(-) diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 95988f50..73532961 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -56,7 +56,8 @@ target_link_libraries(kuka_fri_hw_interface fri::fri_client) add_library(configuration_manager SHARED src/kuka_sunrise/configuration_manager.cpp) -ament_target_dependencies(configuration_manager kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core controller_manager_msgs) +ament_target_dependencies(configuration_manager kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core + controller_manager_msgs) add_executable(robot_manager_node diff --git a/kuka_sunrise_driver/config/forward_controller_config.yaml b/kuka_sunrise_driver/config/forward_controller_config.yaml index d8f99613..4118db8c 100644 --- a/kuka_sunrise_driver/config/forward_controller_config.yaml +++ b/kuka_sunrise_driver/config/forward_controller_config.yaml @@ -1,4 +1,4 @@ -/position_controller: # uniqe names will be available with HWIF parameter interface +/forward_command_controller: ros__parameters: joints: - LBRiiwa7Joint1 diff --git a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml index fbd8a537..cba8d593 100755 --- a/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml +++ b/kuka_sunrise_driver/config/iiwa_ros2_controller_config.yaml @@ -2,9 +2,8 @@ controller_manager: ros__parameters: update_rate: 100 # Hz - position_controller: + joint_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController - # type: forward_command_controller/ForwardCommandController effort_controller: type: effort_controllers/JointEffortController diff --git a/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml b/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml index af9fc401..225d53cf 100644 --- a/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml +++ b/kuka_sunrise_driver/config/joint_trajectory_controller_config.yaml @@ -1,4 +1,4 @@ -/position_controller: # uniqe names will be available with HWIF parameter interface +/joint_trajectory_controller: ros__parameters: joints: - LBRiiwa7Joint1 diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index 8cb31428..bec3aae8 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -17,6 +17,7 @@ #include #include +#include #include "rclcpp/rclcpp.hpp" #include "rclcpp/client.hpp" diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index b8bdeaea..9ec969cd 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -32,8 +32,8 @@ def load_file(absolute_file_path): def generate_launch_description(): controller_config = (get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml") - forward_controller_config = (get_package_share_directory('kuka_sunrise') + - "/config/forward_controller_config.yaml") + # forward_controller_config = (get_package_share_directory('kuka_sunrise') + + # "/config/forward_controller_config.yaml") joint_traj_controller_cofig = (get_package_share_directory('kuka_sunrise') + "/config/joint_trajectory_controller_config.yaml") robot_description_path = (get_package_share_directory('kuka_lbr_iiwa7_support') + @@ -50,9 +50,10 @@ def generate_launch_description(): ), LifecycleNode( namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', - name=['robot_manager'], parameters=[{'controller_ip': ''}, - {'position_controller_name': 'position_controller'}, - {'torque_controller_name': 'position_controller'}] + name=['robot_manager'], + parameters=[{'controller_ip': ''}, + {'position_controller_name': 'joint_trajectory_controller'}, + {'torque_controller_name': ''}] ), Node( package="controller_manager", @@ -62,7 +63,7 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["position_controller", "-c", "/controller_manager", "-p", + arguments=["joint_trajectory_controller", "-c", "/controller_manager", "-p", joint_traj_controller_cofig, "--inactive"] ), Node( diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 788fbf78..426ae7c8 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -225,7 +225,7 @@ bool ConfigurationManager::onControllerNameChangeRequest( return true; } - for (auto controller: response->controller) { + for (auto controller : response->controller) { if (controller_name == controller.name) { if (position) {position_controller_available_ = true;} else { torque_controller_available_ = true; From 18ccf7a69c23faea20ec5122adf3c92de237772e Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 16:18:21 +0200 Subject: [PATCH 58/94] sonar code smells --- .../kuka_fri_hardware_interface.hpp | 52 ++++++++++++------- .../launch/kuka_sunrise_control.launch.py | 10 ++-- .../kuka_sunrise/configuration_manager.cpp | 2 +- sonar-project.properties | 4 +- 4 files changed, 42 insertions(+), 26 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index a612a5a2..1cd13f35 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -41,7 +41,7 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface namespace kuka_sunrise { -enum IOTypes +enum class IOTypes { ANALOG = 0, DIGITAL = 1, @@ -78,6 +78,16 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, void waitForCommand() final; void command() final; + class InvalidGPIOTypeException : public std::runtime_error + { +public: + explicit InvalidGPIOTypeException(const std::string & gpio_type) + : std::runtime_error( + "GPIO type '" + gpio_type + + "' is not supported, possible ones are 'analog', 'digital' or 'boolean'") + {} + }; + private: KUKA::FRI::HWIFClientApplication client_application_; KUKA::FRI::UdpConnection udp_connection_; @@ -109,20 +119,16 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, double drive_state_ = 0; double overlay_type_ = 0; - IOTypes getType(const std::string type_string) + IOTypes getType(const std::string & type_string) const { auto it = types.find(type_string); if (it != types.end()) { return it->second; - } else {throw std::runtime_error("Invalid type for GPIO");} + } else {throw InvalidGPIOTypeException(type_string);} } class GPIOReader { - const std::string name_; - IOTypes type_; - KUKA::FRI::LBRState state_; - public: double data_; GPIOReader(const std::string & name, IOTypes type, const KUKA::FRI::LBRState & state) @@ -130,25 +136,26 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, void getValue() { switch (type_) { - case ANALOG: + case IOTypes::ANALOG: data_ = state_.getAnalogIOValue(name_.c_str()); break; - case DIGITAL: - data_ = state_.getDigitalIOValue(name_.c_str()); + case IOTypes::DIGITAL: + data_ = static_cast(state_.getDigitalIOValue(name_.c_str())); break; - case BOOLEAN: + case IOTypes::BOOLEAN: data_ = state_.getBooleanIOValue(name_.c_str()); break; } } - }; - class GPIOWriter - { +private: const std::string name_; IOTypes type_; - KUKA::FRI::LBRCommand command_; + KUKA::FRI::LBRState state_; + }; + class GPIOWriter + { public: double data_; GPIOWriter( @@ -158,17 +165,22 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, void setValue() { switch (type_) { - case ANALOG: + case IOTypes::ANALOG: command_.setAnalogIOValue(name_.c_str(), data_); break; - case DIGITAL: - command_.setDigitalIOValue(name_.c_str(), data_); + case IOTypes::DIGITAL: + command_.setDigitalIOValue(name_.c_str(), static_cast(data_)); break; - case BOOLEAN: - command_.setBooleanIOValue(name_.c_str(), data_); + case IOTypes::BOOLEAN: + command_.setBooleanIOValue(name_.c_str(), static_cast(data_)); break; } } + +private: + const std::string name_; + IOTypes type_; + KUKA::FRI::LBRCommand command_; }; std::vector gpio_inputs_; diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 9ec969cd..2acb0fbc 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -42,6 +42,8 @@ def generate_launch_description(): Command(['xacro ', str(robot_description_path)]), value_type=str )} + conntroller_manager_node = '/controller_manager' + return LaunchDescription([ Node( package='kuka_sunrise', @@ -58,22 +60,22 @@ def generate_launch_description(): Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "-c", "/controller_manager", "--inactive"] + arguments=["joint_state_broadcaster", "-c", conntroller_manager_node, "--inactive"] ), Node( package="controller_manager", executable="spawner", - arguments=["joint_trajectory_controller", "-c", "/controller_manager", "-p", + arguments=["joint_trajectory_controller", "-c", conntroller_manager_node, "-p", joint_traj_controller_cofig, "--inactive"] ), Node( package="controller_manager", executable="spawner", - arguments=["timing_controller", "-c", "/controller_manager", "--inactive"] + arguments=["timing_controller", "-c", conntroller_manager_node, "--inactive"] ), Node( package="controller_manager", executable="spawner", - arguments=["robot_state_broadcaster", "-c", "/controller_manager", "--inactive"] + arguments=["robot_state_broadcaster", "-c", conntroller_manager_node, "--inactive"] ) ]) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 426ae7c8..aad56534 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -225,7 +225,7 @@ bool ConfigurationManager::onControllerNameChangeRequest( return true; } - for (auto controller : response->controller) { + for (const auto & controller : response->controller) { if (controller_name == controller.name) { if (position) {position_controller_available_ = true;} else { torque_controller_available_ = true; diff --git a/sonar-project.properties b/sonar-project.properties index 38d6e2b8..0bdcc260 100644 --- a/sonar-project.properties +++ b/sonar-project.properties @@ -4,7 +4,7 @@ sonar.projectKey=kroshu_ros2_kuka_drivers sonar.host.url=https://sonarcloud.io -sonar.modules=kuka_sunrise_control,kuka_sunrise_driver, kuka_rsi_hw_interface +sonar.modules=kuka_sunrise_control, kuka_sunrise_driver, kuka_rsi_hw_interface, kuka_controllers kuka_sunrise_control.sonar.projectName=kuka_sunrise_control kuka_sunrise_control.sonar.sources=./robot_control/src,./robot_control/include,./teleop_guided_robot/src,./teleop_guided_robot/include,./teleop_guided_robot/launch @@ -12,6 +12,8 @@ kuka_sunrise_driver.sonar.projectName=kuka_sunrise_driver kuka_sunrise_driver.sonar.sources=./src/kuka_sunrise,./include/kuka_sunrise,./launch kuka_rsi_hw_interface.sonar.projectName=kuka_rsi_hw_interface kuka_rsi_hw_interface.sonar.sources=./src,./include +kuka_controllers.sonar.projectName=kuka_controllers +kuka_controllers.sonar.sources=./src,./include # Encoding of the source code. Default is default system encoding sonar.sourceEncoding=UTF-8 From 3687478b625e3a56bc0f71cb055a8cf13ab64d70 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Thu, 28 Jul 2022 17:09:46 +0200 Subject: [PATCH 59/94] sonar code smell fixes --- .../robot_state_broadcaster.hpp | 4 +-- .../kuka_controllers/timing_controller.hpp | 2 ++ .../src/robot_state_broadcaster.cpp | 36 +++++++++---------- kuka_controllers/src/timing_controller.cpp | 2 -- .../kuka_fri_hardware_interface.hpp | 6 ++-- .../kuka_fri_hardware_interface.cpp | 8 +++-- 6 files changed, 31 insertions(+), 27 deletions(-) diff --git a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp index 429268de..a8c06651 100644 --- a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp +++ b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp @@ -26,6 +26,8 @@ #include "rclcpp/time.hpp" #include "rclcpp/duration.hpp" +#include "pluginlib/class_list_macros.hpp" + namespace kuka_controllers { @@ -52,8 +54,6 @@ class RobotStateBroadcaster : public controller_interface::ControllerInterface controller_interface::CallbackReturn on_init() override; private: - int fri_state_ = 0; - int connection_quality_ = 0; int counter_ = 0; rclcpp::Publisher::SharedPtr robot_state_publisher_; kuka_sunrise_interfaces::msg::RobotState state_msg_; diff --git a/kuka_controllers/include/kuka_controllers/timing_controller.hpp b/kuka_controllers/include/kuka_controllers/timing_controller.hpp index 3d17339b..7e99c8e2 100644 --- a/kuka_controllers/include/kuka_controllers/timing_controller.hpp +++ b/kuka_controllers/include/kuka_controllers/timing_controller.hpp @@ -26,6 +26,8 @@ #include "rclcpp/duration.hpp" #include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "pluginlib/class_list_macros.hpp" + namespace kuka_controllers { class TimingController : public controller_interface::ControllerInterface diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp index d28cb35f..0fbb3468 100644 --- a/kuka_controllers/src/robot_state_broadcaster.cpp +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -36,15 +36,15 @@ const { controller_interface::InterfaceConfiguration config; config.type = controller_interface::interface_configuration_type::INDIVIDUAL; - config.names.push_back("state/session_state"); - config.names.push_back("state/connection_quality"); - config.names.push_back("state/safety_state"); - config.names.push_back("state/command_mode"); - config.names.push_back("state/control_mode"); - config.names.push_back("state/operation_mode"); - config.names.push_back("state/drive_state"); - config.names.push_back("state/overlay_type"); - config.names.push_back("state/tracking_performance"); + config.names.emplace_back("state/session_state"); + config.names.emplace_back("state/connection_quality"); + config.names.emplace_back("state/safety_state"); + config.names.emplace_back("state/command_mode"); + config.names.emplace_back("state/control_mode"); + config.names.emplace_back("state/operation_mode"); + config.names.emplace_back("state/drive_state"); + config.names.emplace_back("state/overlay_type"); + config.names.emplace_back("state/tracking_performance"); return config; } @@ -71,14 +71,14 @@ controller_interface::return_type RobotStateBroadcaster::update( const rclcpp::Duration &) { // TODO(Svastits): measure additional system overload, limit rate? - state_msg_.session_state = state_interfaces_[0].get_value(); - state_msg_.connection_quality = state_interfaces_[1].get_value(); - state_msg_.safety_state = state_interfaces_[2].get_value(); - state_msg_.command_mode = state_interfaces_[3].get_value(); - state_msg_.control_mode = state_interfaces_[4].get_value(); - state_msg_.operation_mode = state_interfaces_[5].get_value(); - state_msg_.drive_state = state_interfaces_[6].get_value(); - state_msg_.overlay_type = state_interfaces_[7].get_value(); + state_msg_.session_state = static_cast(state_interfaces_[0].get_value()); + state_msg_.connection_quality = static_cast(state_interfaces_[1].get_value()); + state_msg_.safety_state = static_cast(state_interfaces_[2].get_value()); + state_msg_.command_mode = static_cast(state_interfaces_[3].get_value()); + state_msg_.control_mode = static_cast(state_interfaces_[4].get_value()); + state_msg_.operation_mode = static_cast(state_interfaces_[5].get_value()); + state_msg_.drive_state = static_cast(state_interfaces_[6].get_value()); + state_msg_.overlay_type = static_cast(state_interfaces_[7].get_value()); state_msg_.tracking_performance = state_interfaces_[8].get_value(); if (counter_++ == 10) { @@ -91,8 +91,6 @@ controller_interface::return_type RobotStateBroadcaster::update( } // namespace kuka_controllers -#include "pluginlib/class_list_macros.hpp" - PLUGINLIB_EXPORT_CLASS( kuka_controllers::RobotStateBroadcaster, controller_interface::ControllerInterface) diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp index a3ce5dc4..8280abe3 100644 --- a/kuka_controllers/src/timing_controller.cpp +++ b/kuka_controllers/src/timing_controller.cpp @@ -81,8 +81,6 @@ controller_interface::return_type TimingController::update( } // namespace kuka_controllers -#include "pluginlib/class_list_macros.hpp" - PLUGINLIB_EXPORT_CLASS( kuka_controllers::TimingController, controller_interface::ControllerInterface) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 1cd13f35..23d7fed2 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -130,7 +130,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, class GPIOReader { public: - double data_; + double & getData() {return data_;} GPIOReader(const std::string & name, IOTypes type, const KUKA::FRI::LBRState & state) : name_(name), type_(type), state_(state) {} void getValue() @@ -152,12 +152,13 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, const std::string name_; IOTypes type_; KUKA::FRI::LBRState state_; + double data_; }; class GPIOWriter { public: - double data_; + double & getData() {return data_;} GPIOWriter( const std::string & name, IOTypes type, KUKA::FRI::LBRCommand & command, double initial_value) @@ -181,6 +182,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, const std::string name_; IOTypes type_; KUKA::FRI::LBRCommand command_; + double data_; }; std::vector gpio_inputs_; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 34026a58..1c8dc18d 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -252,7 +252,9 @@ std::vector KUKAFRIHardwareInterface::export // Register I/O outputs (read access) and inputs (write access) for (size_t i = 0; i < gpio_outputs_.size(); ++i) { - state_interfaces.emplace_back("gpio", "Output" + std::to_string(i), &gpio_outputs_[i].data_); + state_interfaces.emplace_back( + "gpio", "Output" + std::to_string(i), + &gpio_outputs_[i].getData()); } for (size_t i = 0; i < info_.joints.size(); i++) { @@ -278,7 +280,9 @@ export_command_interfaces() // Register I/O inputs (write access) for (size_t i = 0; i < gpio_outputs_.size(); ++i) { - command_interfaces.emplace_back("gpio", "Input" + std::to_string(i), &gpio_inputs_[i].data_); + command_interfaces.emplace_back( + "gpio", "Input" + std::to_string(i), + &gpio_inputs_[i].getData()); } for (size_t i = 0; i < info_.joints.size(); i++) { From a5a10d18b7a1dccae08dfe73d9e7b8b2fa3004d4 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 29 Jul 2022 12:51:59 +0200 Subject: [PATCH 60/94] create struct for robotState --- kuka_controllers/src/timing_controller.cpp | 2 +- .../kuka_fri_hardware_interface.hpp | 27 +++++++----- .../kuka_fri_hardware_interface.cpp | 42 ++++++++++--------- 3 files changed, 39 insertions(+), 32 deletions(-) diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp index 8280abe3..8a695ae0 100644 --- a/kuka_controllers/src/timing_controller.cpp +++ b/kuka_controllers/src/timing_controller.cpp @@ -36,7 +36,7 @@ const { controller_interface::InterfaceConfiguration config; config.type = controller_interface::interface_configuration_type::INDIVIDUAL; - config.names.push_back("timing/receive_multiplier"); + config.names.emplace_back("timing/receive_multiplier"); return config; } diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 23d7fed2..e623f034 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -107,17 +107,22 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, std::vector hw_torques_ext_; std::vector hw_torques_; std::vector hw_effort_command_; - double tracking_performance_ = 1; - - // Enum values represented with doubles (as all interfaces must be pointers to doubles) - double session_state_ = 0; - double connection_quality_ = 0; - double command_mode_ = 0; - double safety_state_ = 0; - double control_mode_ = 0; - double operation_mode_ = 0; - double drive_state_ = 0; - double overlay_type_ = 0; + + struct RobotState + { + double tracking_performance_ = 1; + // Enum values represented with doubles (as all interfaces must be pointers to doubles) + double session_state_ = 0; + double connection_quality_ = 0; + double command_mode_ = 0; + double safety_state_ = 0; + double control_mode_ = 0; + double operation_mode_ = 0; + double drive_state_ = 0; + double overlay_type_ = 0; + }; + + RobotState robot_state_; IOTypes getType(const std::string & type_string) const { diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 1c8dc18d..af03324d 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -177,15 +177,15 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( const double * external_torque = robotState().getExternalTorque(); hw_torques_ext_.assign(external_torque, external_torque + KUKA::FRI::LBRState::NUMBER_OF_JOINTS); - tracking_performance_ = robotState().getTrackingPerformance(); - session_state_ = robotState().getSessionState(); - connection_quality_ = robotState().getConnectionQuality(); - command_mode_ = robotState().getClientCommandMode(); - safety_state_ = robotState().getSafetyState(); - control_mode_ = robotState().getControlMode(); - operation_mode_ = robotState().getOperationMode(); - drive_state_ = robotState().getDriveState(); - overlay_type_ = robotState().getOverlayType(); + robot_state_.tracking_performance_ = robotState().getTrackingPerformance(); + robot_state_.session_state_ = robotState().getSessionState(); + robot_state_.connection_quality_ = robotState().getConnectionQuality(); + robot_state_.command_mode_ = robotState().getClientCommandMode(); + robot_state_.safety_state_ = robotState().getSafetyState(); + robot_state_.control_mode_ = robotState().getControlMode(); + robot_state_.operation_mode_ = robotState().getOperationMode(); + robot_state_.drive_state_ = robotState().getDriveState(); + robot_state_.overlay_type_ = robotState().getOverlayType(); for (size_t i = 0; i < gpio_outputs_.size(); ++i) { gpio_outputs_[i].getValue(); @@ -220,11 +220,11 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) "KUKAFRIHardwareInterface"), "Hardware inactive, exiting updateCommand"); return; } - if (command_mode_ == KUKA::FRI::EClientCommandMode::TORQUE) { + if (robot_state_.command_mode_ == KUKA::FRI::EClientCommandMode::TORQUE) { const double * joint_torques_ = hw_effort_command_.data(); robotCommand().setJointPosition(robotState().getIpoJointPosition()); robotCommand().setTorque(joint_torques_); - } else if (command_mode_ == KUKA::FRI::EClientCommandMode::POSITION) { + } else if (robot_state_.command_mode_ == KUKA::FRI::EClientCommandMode::POSITION) { const double * joint_positions_ = hw_commands_.data(); robotCommand().setJointPosition(joint_positions_); } else { @@ -240,15 +240,17 @@ std::vector KUKAFRIHardwareInterface::export { std::vector state_interfaces; - state_interfaces.emplace_back("state", "session_state", &session_state_); - state_interfaces.emplace_back("state", "connection_quality", &connection_quality_); - state_interfaces.emplace_back("state", "safety_state", &safety_state_); - state_interfaces.emplace_back("state", "command_mode", &command_mode_); - state_interfaces.emplace_back("state", "control_mode", &control_mode_); - state_interfaces.emplace_back("state", "operation_mode", &operation_mode_); - state_interfaces.emplace_back("state", "drive_state", &drive_state_); - state_interfaces.emplace_back("state", "overlay_type", &overlay_type_); - state_interfaces.emplace_back("state", "tracking_performance", &tracking_performance_); + state_interfaces.emplace_back("state", "session_state", &robot_state_.session_state_); + state_interfaces.emplace_back("state", "connection_quality", &robot_state_.connection_quality_); + state_interfaces.emplace_back("state", "safety_state", &robot_state_.safety_state_); + state_interfaces.emplace_back("state", "command_mode", &robot_state_.command_mode_); + state_interfaces.emplace_back("state", "control_mode", &robot_state_.control_mode_); + state_interfaces.emplace_back("state", "operation_mode", &robot_state_.operation_mode_); + state_interfaces.emplace_back("state", "drive_state", &robot_state_.drive_state_); + state_interfaces.emplace_back("state", "overlay_type", &robot_state_.overlay_type_); + state_interfaces.emplace_back( + "state", "tracking_performance", + &robot_state_.tracking_performance_); // Register I/O outputs (read access) and inputs (write access) for (size_t i = 0; i < gpio_outputs_.size(); ++i) { From 5978b05a3e47348eed6804690f5718eae1227a09 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 29 Jul 2022 14:10:40 +0200 Subject: [PATCH 61/94] fix gpio names --- .../kuka_fri_hardware_interface.hpp | 2 ++ .../launch/kuka_sunrise_control.launch.py | 6 ++---- .../kuka_fri_hardware_interface.cpp | 21 +++++++++++-------- 3 files changed, 16 insertions(+), 13 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index e623f034..63925007 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -136,6 +136,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, { public: double & getData() {return data_;} + const std::string & getName() const {return name_;} GPIOReader(const std::string & name, IOTypes type, const KUKA::FRI::LBRState & state) : name_(name), type_(type), state_(state) {} void getValue() @@ -164,6 +165,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, { public: double & getData() {return data_;} + const std::string & getName() const {return name_;} GPIOWriter( const std::string & name, IOTypes type, KUKA::FRI::LBRCommand & command, double initial_value) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 2acb0fbc..a9640dc2 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -32,9 +32,7 @@ def load_file(absolute_file_path): def generate_launch_description(): controller_config = (get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml") - # forward_controller_config = (get_package_share_directory('kuka_sunrise') + - # "/config/forward_controller_config.yaml") - joint_traj_controller_cofig = (get_package_share_directory('kuka_sunrise') + + joint_traj_controller_config = (get_package_share_directory('kuka_sunrise') + "/config/joint_trajectory_controller_config.yaml") robot_description_path = (get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/lbriiwa7.xacro") @@ -66,7 +64,7 @@ def generate_launch_description(): package="controller_manager", executable="spawner", arguments=["joint_trajectory_controller", "-c", conntroller_manager_node, "-p", - joint_traj_controller_cofig, "--inactive"] + joint_traj_controller_config, "--inactive"] ), Node( package="controller_manager", diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index af03324d..91440524 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -187,8 +187,8 @@ hardware_interface::return_type KUKAFRIHardwareInterface::read( robot_state_.drive_state_ = robotState().getDriveState(); robot_state_.overlay_type_ = robotState().getOverlayType(); - for (size_t i = 0; i < gpio_outputs_.size(); ++i) { - gpio_outputs_[i].getValue(); + for (auto & output : gpio_outputs_) { + output.getValue(); } return hardware_interface::return_type::OK; } @@ -234,6 +234,9 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) for (size_t i = 0; i < gpio_inputs_.size(); ++i) { gpio_inputs_[i].setValue(); } + for (auto & input : gpio_inputs_) { + input.setValue(); + } } std::vector KUKAFRIHardwareInterface::export_state_interfaces() @@ -252,11 +255,11 @@ std::vector KUKAFRIHardwareInterface::export "state", "tracking_performance", &robot_state_.tracking_performance_); - // Register I/O outputs (read access) and inputs (write access) - for (size_t i = 0; i < gpio_outputs_.size(); ++i) { + // Register I/O outputs (read access) + for (auto & output : gpio_outputs_) { state_interfaces.emplace_back( - "gpio", "Output" + std::to_string(i), - &gpio_outputs_[i].getData()); + "gpio", output.getName(), + &output.getData()); } for (size_t i = 0; i < info_.joints.size(); i++) { @@ -281,10 +284,10 @@ export_command_interfaces() command_interfaces.emplace_back("timing", "receive_multiplier", &receive_multiplier_); // Register I/O inputs (write access) - for (size_t i = 0; i < gpio_outputs_.size(); ++i) { + for (auto & input : gpio_inputs_) { command_interfaces.emplace_back( - "gpio", "Input" + std::to_string(i), - &gpio_inputs_[i].getData()); + "gpio", input.getName(), + &input.getData()); } for (size_t i = 0; i < info_.joints.size(); i++) { From a7837e412b932157e9728866df2bae4e7fe8346b Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 29 Jul 2022 14:28:25 +0200 Subject: [PATCH 62/94] flake8 --- kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index a9640dc2..c2b6f4d8 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -33,7 +33,7 @@ def generate_launch_description(): controller_config = (get_package_share_directory('kuka_sunrise') + "/config/iiwa_ros2_controller_config.yaml") joint_traj_controller_config = (get_package_share_directory('kuka_sunrise') + - "/config/joint_trajectory_controller_config.yaml") + "/config/joint_trajectory_controller_config.yaml") robot_description_path = (get_package_share_directory('kuka_lbr_iiwa7_support') + "/urdf/lbriiwa7.xacro") robot_description = {'robot_description': ParameterValue( From f4eb9a52d26cfc5063d600f1693177a7c6a374a4 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 29 Jul 2022 14:53:50 +0200 Subject: [PATCH 63/94] fix GPIO class member types --- .../include/kuka_sunrise/kuka_fri_hardware_interface.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index 63925007..c56cc3a1 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -157,7 +157,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, private: const std::string name_; IOTypes type_; - KUKA::FRI::LBRState state_; + const KUKA::FRI::LBRState & state_; double data_; }; @@ -188,7 +188,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, private: const std::string name_; IOTypes type_; - KUKA::FRI::LBRCommand command_; + KUKA::FRI::LBRCommand & command_; double data_; }; From bd1ed935190c41b8af3afa5d270d90f584ac1a5b Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 29 Jul 2022 15:13:27 +0200 Subject: [PATCH 64/94] remove duplicated for loop --- .../src/kuka_sunrise/kuka_fri_hardware_interface.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index 91440524..a9071b47 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -230,10 +230,6 @@ void KUKAFRIHardwareInterface::updateCommand(const rclcpp::Time &) } else { RCLCPP_ERROR(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Unsupported command mode"); } - - for (size_t i = 0; i < gpio_inputs_.size(); ++i) { - gpio_inputs_[i].setValue(); - } for (auto & input : gpio_inputs_) { input.setValue(); } From dcc45791443f34f8a3d0486f2b03463676d3557a Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 5 Aug 2022 14:11:54 +0200 Subject: [PATCH 65/94] rollback for activation --- .../src/kuka_sunrise/robot_manager_node.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 3c2b2bcf..c4d7a18c 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -119,7 +119,6 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) return ERROR; } RCLCPP_INFO(get_logger(), "Successfully connected to FRI"); - // TODO(resizoltan) get IO configuration if (result == SUCCESS) { auto trigger_request = @@ -224,6 +223,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) // Start FRI (in monitoring mode) if (!robot_manager_->startFRI()) { RCLCPP_ERROR(get_logger(), "Could not start FRI"); + // 'unset config' does not exist, safe to return return FAILURE; } RCLCPP_INFO(get_logger(), "Started FRI"); @@ -238,6 +238,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) change_hardware_state_client_, hw_request, 0, 2000); if (!hw_response || !hw_response->ok) { RCLCPP_ERROR(get_logger(), "Could not activate hardware interface"); + this->on_deactivate(get_current_state()); return FAILURE; } RCLCPP_INFO(get_logger(), "Activated LBR iiwa hardware interface"); @@ -254,6 +255,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) change_controller_state_client_, controller_request, 0, 2000); if (!controller_response || !controller_response->ok) { RCLCPP_ERROR(get_logger(), "Could not start joint state broadcaster"); + this->on_deactivate(get_current_state()); return FAILURE; } @@ -270,12 +272,14 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) change_controller_state_client_, controller_request, 0, 2000); if (!controller_response || !controller_response->ok) { RCLCPP_ERROR(get_logger(), "Could not activate controller"); + this->on_deactivate(get_current_state()); return FAILURE; } command_state_changed_publisher_->on_activate(); // Start commanding mode if (!activate()) { + this->on_deactivate(get_current_state()); return FAILURE; } @@ -301,6 +305,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) } // Deactivate hardware interface + // If it is inactive, deactivation will also succeed auto hw_request = std::make_shared(); hw_request->name = "iiwa_hardware"; @@ -317,7 +322,9 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) // Stop RT controllers auto controller_request = std::make_shared(); - controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + // With best effort strictness, deactivation succeeds if specific controller is not active + controller_request->strictness = + controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT; controller_request->deactivate_controllers = std::vector{controller_name_}; auto controller_response = kuka_sunrise::sendRequest( @@ -327,7 +334,9 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) return ERROR; } - command_state_changed_publisher_->on_deactivate(); + if (command_state_changed_publisher_->is_activated()) { + command_state_changed_publisher_->on_deactivate(); + } return SUCCESS; } From 982601e113537b92e3f12c75f11285b610ac9d9e Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 5 Aug 2022 14:26:39 +0200 Subject: [PATCH 66/94] configure rollack fix --- kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index c4d7a18c..0f167a9b 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -148,7 +148,8 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) // Stop non-RT controllers auto controller_request = std::make_shared(); - controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + // With best effort strictness, cleanup succeeds if specific controller is not active + controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT; controller_request->deactivate_controllers = std::vector{"timing_controller", "robot_state_broadcaster"}; auto controller_response = @@ -160,6 +161,7 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) } // Cleanup hardware interface + // If it is inactive, cleanup will also succeed auto hw_request = std::make_shared(); hw_request->name = "iiwa_hardware"; From fc9294f8f95141ebd9b83cb8a41fff74b5e2b314 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 5 Aug 2022 14:44:34 +0200 Subject: [PATCH 67/94] uncrustify --- kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 0f167a9b..a6064c48 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -149,7 +149,8 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) auto controller_request = std::make_shared(); // With best effort strictness, cleanup succeeds if specific controller is not active - controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT; + controller_request->strictness = + controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT; controller_request->deactivate_controllers = std::vector{"timing_controller", "robot_state_broadcaster"}; auto controller_response = @@ -208,7 +209,6 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) { - // TODO(Svastits): implement rollback mechanism if (!robot_manager_->isConnected()) { RCLCPP_ERROR(get_logger(), "not connected"); return ERROR; From 3c79dd055066130e9afb95ed924a33d296f0e55b Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 15 Aug 2022 10:41:34 +0200 Subject: [PATCH 68/94] add namespace to node names --- .../launch/kuka_sunrise.launch.py | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py index 31cc711c..b30ac68b 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py @@ -14,6 +14,9 @@ from launch import LaunchDescription +from ament_index_python.packages import get_package_share_directory +import launch.actions +import launch.substitutions import launch_ros.actions @@ -22,10 +25,15 @@ def generate_launch_description(): return LaunchDescription([ + launch.actions.DeclareLaunchArgument( + 'node_prefix', + default_value=[''], + description='prefix for node names'), launch_ros.actions.LifecycleNode( - namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', - name=['robot_manager'], parameters=[{'controller_ip': ''}]), + namespace="", package='kuka_sunrise', executable='robot_manager_node', output='screen', + name=[launch.substitutions.LaunchConfiguration('node_prefix'), 'robot_manager'], + parameters=[fri_config_file]), launch_ros.actions.LifecycleNode( - namespace='', package='kuka_sunrise', executable='robot_control_node', output='screen', - name=['robot_control']) + namespace="", package='kuka_sunrise', executable='robot_control_node', output='screen', + name=[launch.substitutions.LaunchConfiguration('node_prefix'), 'robot_control']) ]) From 815f7d1d3b133088e610cd263799b936fa73859a Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 15 Aug 2022 11:38:32 +0200 Subject: [PATCH 69/94] fix activation order --- .../launch/kuka_sunrise_control.launch.py | 3 ++- .../src/kuka_sunrise/robot_manager_node.cpp | 17 ++++++++--------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index c2b6f4d8..dceed63d 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -20,6 +20,7 @@ from launch_ros.descriptions import ParameterValue from launch.substitutions import Command +fri_config_file = get_package_share_directory('kuka_sunrise') + "/config/fri_config.yaml" def load_file(absolute_file_path): try: @@ -51,7 +52,7 @@ def generate_launch_description(): LifecycleNode( namespace='', package='kuka_sunrise', executable='robot_manager_node', output='screen', name=['robot_manager'], - parameters=[{'controller_ip': ''}, + parameters=[fri_config_file, {'position_controller_name': 'joint_trajectory_controller'}, {'torque_controller_name': ''}] ), diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index a6064c48..380feaca 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -222,14 +222,6 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) } RCLCPP_INFO(get_logger(), "Successfully set FRI config"); - // Start FRI (in monitoring mode) - if (!robot_manager_->startFRI()) { - RCLCPP_ERROR(get_logger(), "Could not start FRI"); - // 'unset config' does not exist, safe to return - return FAILURE; - } - RCLCPP_INFO(get_logger(), "Started FRI"); - // Activate hardware interface auto hw_request = std::make_shared(); @@ -245,6 +237,14 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) } RCLCPP_INFO(get_logger(), "Activated LBR iiwa hardware interface"); + // Start FRI (in monitoring mode) + if (!robot_manager_->startFRI()) { + RCLCPP_ERROR(get_logger(), "Could not start FRI"); + // 'unset config' does not exist, safe to return + return FAILURE; + } + RCLCPP_INFO(get_logger(), "Started FRI"); + // Activate joint state broadcaster // The other controller must be started later so that it can initialize internal state // with broadcaster information @@ -261,7 +261,6 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) return FAILURE; } - auto position_controller_name = this->get_parameter("position_controller_name").as_string(); auto torque_controller_name = this->get_parameter("torque_controller_name").as_string(); controller_name_ = (this->get_parameter("command_mode").as_string() == From 7f194bb47d0e502e3dedbf0911aa137c29b9d0ef Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 15 Aug 2022 14:55:22 +0200 Subject: [PATCH 70/94] publish robot description --- kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index dceed63d..72a7ae76 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -56,6 +56,13 @@ def generate_launch_description(): {'position_controller_name': 'joint_trajectory_controller'}, {'torque_controller_name': ''}] ), + # robot_description topic is needed for rqt_joint_trajectory_controller + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + output='both', + parameters=[robot_description] + ), Node( package="controller_manager", executable="spawner", From d6dfc592077fdcf0ea2b12b32f43004bce58afd5 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 15 Aug 2022 16:07:45 +0200 Subject: [PATCH 71/94] add comments --- .../src/kuka_sunrise/kuka_fri_hardware_interface.cpp | 1 - kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp | 3 ++- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index a9071b47..b9e38e4f 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -118,7 +118,6 @@ CallbackReturn KUKAFRIHardwareInterface::on_activate(const rclcpp_lifecycle::Sta return CallbackReturn::FAILURE; } this->ActivatableInterface::activate(); - RCLCPP_INFO(rclcpp::get_logger("KUKAFRIHardwareInterface"), "Activated client"); return CallbackReturn::SUCCESS; } diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 380feaca..f7dc50c4 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -26,7 +26,7 @@ RobotManagerNode::RobotManagerNode() // Therefore controllers are loaded and configured at startup, only activation // and deactivation is managed by this node // There are two kind of controllers used: - // - RT: joint state broadcaster and joint state/effort commander + // - RT: joint state broadcaster and joint position/effort commander // - non-RT: configuration (workaround until runtime parameters are enabled) // and robot state broadcaster // RT controllers are started after interface activation @@ -206,6 +206,7 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) return SUCCESS; } +// TODO(Svastits): activation fails after deactivation rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) { From 7033aca9e865bf77f033035db829a869da2cef9a Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 15 Aug 2022 16:28:36 +0200 Subject: [PATCH 72/94] add missing broadcaster deactivation --- kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index f7dc50c4..9d5414e8 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -327,7 +327,8 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) // With best effort strictness, deactivation succeeds if specific controller is not active controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT; - controller_request->deactivate_controllers = std::vector{controller_name_}; + controller_request->deactivate_controllers = + std::vector{controller_name_, "joint_state_broadcaster"}; auto controller_response = kuka_sunrise::sendRequest( change_controller_state_client_, controller_request, 0, 2000); From f13c2e325d9e529303bb51aea2726d087a75d2c5 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Mon, 15 Aug 2022 16:34:30 +0200 Subject: [PATCH 73/94] remove unused clients and servers --- .../kuka_sunrise/robot_manager_node.hpp | 5 --- .../src/kuka_sunrise/robot_manager_node.cpp | 45 ------------------- 2 files changed, 50 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index bec3aae8..79bcd69b 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -65,21 +65,16 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat private: std::shared_ptr robot_manager_; std::unique_ptr configuration_manager_; - rclcpp::Client::SharedPtr change_robot_control_state_client_; rclcpp::Client::SharedPtr set_parameter_client_; - rclcpp::Client::SharedPtr set_commanding_state_client_; rclcpp::Client::SharedPtr change_hardware_state_client_; rclcpp::Client::SharedPtr change_controller_state_client_; rclcpp::CallbackGroup::SharedPtr cbg_; - rclcpp::Service::SharedPtr change_robot_commanding_state_service_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr command_state_changed_publisher_; std::string controller_name_; - bool requestRobotControlNodeStateTransition(std::uint8_t transition); - bool setRobotControlNodeCommandState(bool active); void handleControlEndedError(); void handleFRIEndedError(); }; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 9d5414e8..8f36e4c5 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -40,27 +40,12 @@ RobotManagerNode::RobotManagerNode() auto qos = rclcpp::QoS(rclcpp::KeepLast(10)); qos.reliable(); cbg_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - change_robot_control_state_client_ = this->create_client( - "robot_control/change_state", qos.get_rmw_qos_profile(), cbg_); - set_commanding_state_client_ = this->create_client( - "robot_control/set_commanding_state", qos.get_rmw_qos_profile(), cbg_); change_hardware_state_client_ = this->create_client( "controller_manager/set_hardware_component_state", qos.get_rmw_qos_profile(), cbg_); change_controller_state_client_ = this->create_client( "controller_manager/switch_controller", qos.get_rmw_qos_profile(), cbg_); - auto command_srv_callback = [this]( - std_srvs::srv::SetBool::Request::SharedPtr request, - std_srvs::srv::SetBool::Response::SharedPtr response) { - if (request->data == true) { - response->success = this->activate(); - } else { - response->success = this->deactivate(); - } - }; - change_robot_commanding_state_service_ = this->create_service( - "robot_manager/set_commanding_state", command_srv_callback); command_state_changed_publisher_ = this->create_publisher( "robot_manager/commanding_state_changed", qos); set_parameter_client_ = this->create_client( @@ -382,36 +367,6 @@ bool RobotManagerNode::deactivate() return true; } -bool RobotManagerNode::requestRobotControlNodeStateTransition(std::uint8_t transition) -{ - auto request = std::make_shared(); - request->transition.id = transition; - - auto response = kuka_sunrise::sendRequest( - change_robot_control_state_client_, request, 2000, 3000); - - if (!response || !response->success) { - RCLCPP_ERROR(get_logger(), "Could not change robot control state"); - return false; - } - return true; -} - -bool RobotManagerNode::setRobotControlNodeCommandState(bool active) -{ - auto request = std::make_shared(); - request->data = active; - - auto response = kuka_sunrise::sendRequest( - set_commanding_state_client_, request, 0, 1000); - - if (!response || !response->success) { - RCLCPP_ERROR(get_logger(), "Could not set robot command state"); - return false; - } - return true; -} - void RobotManagerNode::handleControlEndedError() { // TODO(Svastits): deactivate managers by internal control ended error From 9aa8cbfacaf48a0f299ceaed89b14925d0dd2611 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 16 Aug 2022 11:08:26 +0200 Subject: [PATCH 74/94] deactivate by control ended --- .../kuka_sunrise/robot_manager_node.hpp | 4 ++-- .../src/kuka_sunrise/robot_manager_node.cpp | 22 ++++++------------- 2 files changed, 9 insertions(+), 17 deletions(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index 79bcd69b..3c7392b3 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -59,8 +59,8 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &); - bool activate(); - bool deactivate(); + bool activateControl(); + bool deactivateControl(); private: std::shared_ptr robot_manager_; diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index 8f36e4c5..d42360f9 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -218,7 +218,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) change_hardware_state_client_, hw_request, 0, 2000); if (!hw_response || !hw_response->ok) { RCLCPP_ERROR(get_logger(), "Could not activate hardware interface"); - this->on_deactivate(get_current_state()); + // 'unset config' does not exist, safe to return return FAILURE; } RCLCPP_INFO(get_logger(), "Activated LBR iiwa hardware interface"); @@ -226,7 +226,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) // Start FRI (in monitoring mode) if (!robot_manager_->startFRI()) { RCLCPP_ERROR(get_logger(), "Could not start FRI"); - // 'unset config' does not exist, safe to return + this->on_deactivate(get_current_state()); return FAILURE; } RCLCPP_INFO(get_logger(), "Started FRI"); @@ -265,7 +265,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) command_state_changed_publisher_->on_activate(); // Start commanding mode - if (!activate()) { + if (!activateControl()) { this->on_deactivate(get_current_state()); return FAILURE; } @@ -281,7 +281,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) return ERROR; } - if (this->isActive() && !this->deactivate()) { + if (this->isActive() && !this->deactivateControl()) { RCLCPP_ERROR(get_logger(), "Could not deactivate control"); return ERROR; } @@ -329,7 +329,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &) return SUCCESS; } -bool RobotManagerNode::activate() +bool RobotManagerNode::activateControl() { this->ActivatableInterface::activate(); if (!robot_manager_->isConnected()) { @@ -348,7 +348,7 @@ bool RobotManagerNode::activate() return true; } -bool RobotManagerNode::deactivate() +bool RobotManagerNode::deactivateControl() { if (!robot_manager_->isConnected()) { RCLCPP_ERROR(get_logger(), "Not connected"); @@ -369,21 +369,13 @@ bool RobotManagerNode::deactivate() void RobotManagerNode::handleControlEndedError() { - // TODO(Svastits): deactivate managers by internal control ended error - // currently the hardware interface deactivation fails with timeout - // (possible threading issue) RCLCPP_INFO(get_logger(), "Control ended"); - if (this->on_deactivate(get_current_state()) != SUCCESS) { - RCLCPP_FATAL(get_logger(), "Could not deactivate managers"); - } + this->LifecycleNode::deactivate(); } void RobotManagerNode::handleFRIEndedError() { RCLCPP_INFO(get_logger(), "FRI ended"); - if (get_current_state().label() == "active") { - deactivate(); - } this->LifecycleNode::deactivate(); } From 0d6f4065a68c654fdce9fbb36fe438950e9f2e15 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 16 Aug 2022 11:58:15 +0200 Subject: [PATCH 75/94] TODO, flake8 --- kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp | 2 ++ kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py | 1 + 2 files changed, 3 insertions(+) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index 3c7392b3..e1e9bf1b 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -59,6 +59,8 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &); + // TODO(Svastits): implement on_error callback to clean up node + bool activateControl(); bool deactivateControl(); diff --git a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py index 72a7ae76..7461b5ad 100644 --- a/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py +++ b/kuka_sunrise_driver/launch/kuka_sunrise_control.launch.py @@ -22,6 +22,7 @@ fri_config_file = get_package_share_directory('kuka_sunrise') + "/config/fri_config.yaml" + def load_file(absolute_file_path): try: with open(absolute_file_path, 'r') as file: From db8a213cf57d9323b6263f5266732348b35c7461 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 16 Aug 2022 13:07:35 +0200 Subject: [PATCH 76/94] flake8 --- .../launch/keyboard_guided_robot.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py b/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py index 634c5c9a..2db56fd4 100644 --- a/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py +++ b/kuka_sunrise_control/teleop_guided_robot/launch/keyboard_guided_robot.launch.py @@ -31,8 +31,8 @@ def generate_launch_description(): joint_controller = launch_ros.actions.LifecycleNode( namespace="", package='robot_control', executable='interpolating_controller', name='joint_controller', remappings=[('measured_joint_state', 'lbr_joint_state'), - ('joint_command', 'lbr_joint_command')] - parameters=[robot_config_file], output='screen', + ('joint_command', 'lbr_joint_command')], + parameters=[robot_config_file], output='screen' ) keyboard_control = launch_ros.actions.LifecycleNode( From bb4ba4950bd2ce029c79f10f0e40c4d4d7cf7865 Mon Sep 17 00:00:00 2001 From: Gergely Kovacs Date: Thu, 12 Jan 2023 09:34:39 +0100 Subject: [PATCH 77/94] set scheduler prio --- .../src/kuka_sunrise/kuka_fri_hardware_interface.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp index b9e38e4f..6001ef04 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/kuka_fri_hardware_interface.cpp @@ -108,6 +108,14 @@ CallbackReturn KUKAFRIHardwareInterface::on_init( } } + struct sched_param param; + param.sched_priority = 95; + if (sched_setscheduler(0, SCHED_FIFO, ¶m) == -1) { + RCLCPP_ERROR(rclcpp::get_logger("KukaRoXHardwareInterface"), "setscheduler error"); + RCLCPP_ERROR(rclcpp::get_logger("KukaRoXHardwareInterface"), strerror(errno)); + return CallbackReturn::ERROR; + } + return CallbackReturn::SUCCESS; } From c7db0e670472c79709c261a125387d4893025f78 Mon Sep 17 00:00:00 2001 From: Gergely Kovacs Date: Thu, 12 Jan 2023 11:15:23 +0100 Subject: [PATCH 78/94] fix package rename merge --- .../launch/keyboard_guided_robot.launch.py | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py b/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py index cfb3d170..2db56fd4 100644 --- a/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py +++ b/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py @@ -21,8 +21,8 @@ def generate_launch_description(): - kuka_sunrise_dir = get_package_share_directory('kuka_sunrise') robot_config_file = get_package_share_directory('robot_control') + "/config/lbr_iiwa.yaml" + kuka_sunrise_dir = get_package_share_directory('kuka_sunrise') kuka_sunrise_interface = IncludeLaunchDescription( PythonLaunchDescriptionSource([kuka_sunrise_dir, '/launch/kuka_sunrise.launch.py']) @@ -30,10 +30,10 @@ def generate_launch_description(): joint_controller = launch_ros.actions.LifecycleNode( namespace="", package='robot_control', executable='interpolating_controller', - parameters=[robot_config_file], name='joint_controller', output='both', - remappings=[('measured_joint_state', 'lbr_joint_state'), - ('joint_command', 'lbr_joint_command')] - ) + name='joint_controller', remappings=[('measured_joint_state', 'lbr_joint_state'), + ('joint_command', 'lbr_joint_command')], + parameters=[robot_config_file], output='screen' + ) keyboard_control = launch_ros.actions.LifecycleNode( package='teleop_guided_robot', executable='keyboard_control', output='screen', @@ -44,7 +44,10 @@ def generate_launch_description(): package='teleop_guided_robot', executable='system_manager', output='screen', name='system_manager', namespace="" ) - + """ + key_teleop = launch_ros.actions.Node( + package='key_teleop', executable='key_teleop', output='screen', name='key_teleop') + """ return LaunchDescription([ kuka_sunrise_interface, joint_controller, From b5fce44d24d121d2922eeff09c37a6073c0c3034 Mon Sep 17 00:00:00 2001 From: Gergely Kovacs Date: Thu, 12 Jan 2023 11:21:02 +0100 Subject: [PATCH 79/94] fix rename folder merge 2 --- .../teleop_guided_robot/launch/sunrise_control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py b/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py index e0fe41cd..2e140adb 100644 --- a/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py +++ b/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py @@ -60,8 +60,8 @@ def generate_launch_description(): joint_controller = launch_ros.actions.LifecycleNode( namespace="", package='robot_control', executable='interpolating_controller', + arguments=['--ros-args', '--log-level', 'info'], parameters=[robot_config_file], name='joint_controller', output='both', - parameters=[robot_config_file, {"velocity_factors": [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5]}], remappings=[('measured_joint_state', 'lbr_joint_state'), ('joint_command', 'lbr_joint_command')] ) From 4951e3552c6ef76b0199703f1665ebe10b2a31b8 Mon Sep 17 00:00:00 2001 From: Gergely Kovacs Date: Thu, 12 Jan 2023 12:26:45 +0100 Subject: [PATCH 80/94] fix cmake merge --- kuka_sunrise_driver/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index 656ee606..d345b502 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -85,8 +85,8 @@ ament_target_dependencies(lifecycle_client_node rclcpp rclcpp_lifecycle std_msgs pluginlib_export_plugin_description_file(hardware_interface hardware_interface.xml) -install(TARGETS robot_manager robot_control_client robot_manager_node robot_control_node position_controller_node torque_controller_node - lifecycle_client_node +install(TARGETS robot_manager kuka_fri_hw_interface robot_manager_node position_controller_node torque_controller_node + lifecycle_client_node sunrise_control_node DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch config From a1a41dedea9e0b380d5158c952442a8a4e6c0131 Mon Sep 17 00:00:00 2001 From: Svastits Date: Fri, 20 Jan 2023 11:53:04 +0100 Subject: [PATCH 81/94] fix readme --- fri_client/README.md | 110 +----------------- fri_client/include/fri/friClientApplication.h | 8 +- fri_client/package.xml | 2 +- 3 files changed, 6 insertions(+), 114 deletions(-) diff --git a/fri_client/README.md b/fri_client/README.md index 2b1edabe..e8e66348 100644 --- a/fri_client/README.md +++ b/fri_client/README.md @@ -1,109 +1 @@ -# Fast Robot Interface -The Fast Robot Interface (FRI) library allows for hard real time communication to the KUKA LBR Med, see KUKA's [paper](http://www.best-of-robotics.org/pages/publications/KUKA_FRI_from_WS_Proceedings_ICRA2010.pdf). This folder contains the C++ client side library to setup the UDP connection to the LBR Med. However, hard real time is only supported if the FRI is compiled on a real time OS. -## Build and Installation -Other than what KUKA provides, our FRI comes with CMake support. This allows for cross-platform compatability, therefore, the [Cross Platform Build and Installation](#cross-platform-build-and-installation) instructions are the same for Linux and Windows. However, the prerequisites are differntly obtained. How to obtain the prerequisites is explained in [Linux Prerequisites](#linux-prerequisites) and [Windows Prerequisites](#windows-prerequisites), respectively. -### Linux Prerequisites -Skip any of these if already satisfied. -* Install Git. In a terminal, run `sudo apt install git` -* Install CMake. In a terminal, run `sudo apt install cmake` -### Windows Prerequisites -Skip any of these if already satisfied. - * Install the new Windows Terminal. Search for `Microsoft Store` in Start and open it. Therein, search for `Windows Terminal`, and install it - * Install Chocolatey by following the [instructions](https://chocolatey.org/install) - * Install Git. In an administrative Windows Terminal, run `choco install git`. - * Install CMake. In an administrative Windows Terminal, run `choco install cmake`. Add CMake to your Path. Therefore, search for `Edit the system environment variables` in Start, and open it. Open `Environment Variables...`, and double click on `Path` under System variables. Click on `New`, and add `C:\Program Files\CMake\bin` (usually CMake is installed there, might differ) -### Cross Platform Build and Installation -Clone this repository -```shell -git clone https://github.com/KCL-BMEIS/FastRobotInterface.git -``` -Build and install the FRI library -```shell -cd FastRobotInterface -mkdir build -cd build -cmake .. -cmake --build . --config Release --target install # builds and installs the FRI library in Release mode -``` -## Usage -The FRI comes with [example apps](#example-apps). These apps require some [prerequisites](#prerequisites) that are explained below. -### Prerequisites -Follow the [Build and Installation](#build-and-installation) instructions for your OS. Install [Sunrise Workbench](#sunrise-workbench) on your computer. This step requires Windows as OS. -#### Sunrise Workbench -Sunrise Workbench is KUKA's Java IDE that allows you to program the LBR Med. -* Download it from the [RViM shared folder](https://emckclac.sharepoint.com/:u:/s/MT-BMEIS-RVIM/ETBf6gp3Ko5EvtJVziR8MZ4BLdeX8ysF13jTVmVreq0iZA?e=XJyagD) -* Extract the .zip file and run the Sunrise Workbench Setup -* Follow the install instructions -### Example Apps -Exemplary applications for the C++ client side are located inside the [apps](https://github.com/KCL-BMEIS/FastRobotInterface/tree/master/apps) folder. Each of these apps has a Java equivalent for the server side. -#### Connect Laptop -* Connect your laptop, therefore, establish an Ethernet connection to connector X66 at the KUKA controller -* The KUKA controller's default IP is 172.31.1.147. Configure the same network on your laptop, therefore - * On Windows - * Search for `View network connections` in Start and open it - * Right click on the Ethernet connection and open `Properties` - * Double click Internet Protocol Version 4 (TCP/IPv4) and set the IP address to `172.31.1.148` and the Subnet mask to `255.255.0.0` - * On Ubuntu 16 (might differ for other Linux distributions) - * Search for `System Settings` and open it - * Go to Network -> Wired -> Options - * Go to the IPv4 Settings tab and set the IP address to `172.31.1.148` and the Netmask to `255.255.0.0` -#### Server Side - KUKA Controller -You will have to follow the instructions in [Connect Laptop](#connect-laptop). The FRI has to be installed on the controller. Therefore, the [Sunrise Workbench](#sunrise-workbench) IDE is used. -* Open the Sunrise Workbench -* Create a new project, therefore - * Click File -> New -> Sunrise project - * Leave the default IP (172.31.1.147) and click Next - * Give your project a name, e.g. FRI and click Next - * Select LBR Med 7 R800 and click Next - * Under Media Flange, select Medien-Flansch Inside elektrisch, and click Next - * Click Finish (might take some time). Select RoboticsAPI Application, and press Next - * Click Finish -* Setup the KUKA controller, therefore - * Double click the StationSetup.cat under FRI in the Package Explorer and add the LBR Med 7 R800 to the Topolgy (below left) - * Remove the LBR_Med_7_R800_2, which has no Media Flange, and which we are not using (below right) -

-

-
-
- * In the Software tab, make sure that the checker boxes for the FRI extensions are selected (below left) - * In the Configurations tab, make sure that the IP is set to 172.31.1.147 (below right) - * Save the StationSetup.cat via `Ctrl + s` -
-

-
-
- * In the Installation tab, click Install (below left) - * Synchronize your project with the KUKA controller (below right) -
-

-
-
-#### Client Side - Laptop -You will have to follow the instructions in [Connect Laptop](#connect-laptop), and make sure that the FRI was installed to the KUKA controller, according to [Server Side - KUKA Controller](#server-side---kuka-controller). The client side requires to build the [apps](https://github.com/KCL-BMEIS/FastRobotInterface/tree/master/apps), which requires that the FRI was installed according to [Build and Installation](#build-and-installation). Then, open a terminal and do -```shell -cd apps -mkdir build -cd build -cmake -DCMAKE_PREFIX_PATH='path/to/lib' .. # on Windows this should be 'C:\Program Files (x86)\FastRobotInterface' - # on Linux this should be '/usr/local' -cmake --build . --config Release # builds the apps in Release mode -``` -#### Run the Apps -To run one of the example [apps](https://github.com/KCL-BMEIS/FastRobotInterface/tree/master/apps), they have to be started on the smartHMI (KUKA's smartpad), as well as on the laptop. -* On the smartHMI - * Select an Application (left below), e.g. the LBRJointSineOverlay - * Press one of the enabling switches half way (grey buttons on the back of the smartHMI). The joint control A1-A7 will light up (center below) - * Press and hold the play button (below right), and the enabling switch -

-
-

-
-
-* On the laptop open a terminal, and run - -```shell -cd apps/build # on Linux -cd apps/build/Release # on Windows -./lbrjointsineoverlay -``` -The robot should now be controlled by your Laptop, well done 😄! For open questions please leave an [Issue](https://github.com/KCL-BMEIS/FastRobotInterface/issues). +The FRI client package was copied from https://github.com/KCL-BMEIS/fri and integrated into a ROS2 package. \ No newline at end of file diff --git a/fri_client/include/fri/friClientApplication.h b/fri_client/include/fri/friClientApplication.h index 538e79d4..44f030a7 100644 --- a/fri_client/include/fri/friClientApplication.h +++ b/fri_client/include/fri/friClientApplication.h @@ -5,10 +5,10 @@ agreement or other license is obtained by KUKA Roboter GmbH, Augsburg, Germany. SCOPE -The software “KUKA Sunrise.Connectivity FRI Client SDK” is targeted to work in -conjunction with the “KUKA Sunrise.Connectivity FastRobotInterface” toolkit. -In the following, the term “software” refers to all material directly -belonging to the provided SDK “Software development kit”, particularly source +The software "KUKA Sunrise.Connectivity FRI Client SDK" is targeted to work in +conjunction with the "KUKA Sunrise.Connectivity FastRobotInterface" toolkit. +In the following, the term "software" refers to all material directly +belonging to the provided SDK "Software development kit", particularly source code, libraries, binaries, manuals and technical documentation. COPYRIGHT diff --git a/fri_client/package.xml b/fri_client/package.xml index 4cf6d17d..5515fca6 100644 --- a/fri_client/package.xml +++ b/fri_client/package.xml @@ -5,7 +5,7 @@ 0.0.0 FRI client library rosdeveloper - Apache 2.0 + MIT ament_cmake From d5cbec8871f2a4b5e4feafbc9f05f85e087b9646 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 20 Jan 2023 15:18:19 +0100 Subject: [PATCH 82/94] remove nanopb src --- fri_client/CMakeLists.txt | 31 +- fri_client/src/FRIMessages.pb.c | 32 +- fri_client/src/FRIMessages.pb.h | 32 +- fri_client/src/friCommandMessageEncoder.cpp | 2 +- .../src/friMonitoringMessageDecoder.cpp | 2 +- fri_client/src/pb_frimessages_callbacks.c | 4 +- fri_client/src/pb_frimessages_callbacks.h | 2 +- fri_client/third_party/nanopb/.gitignore | 2 - fri_client/third_party/nanopb/CHANGELOG.txt | 150 --- fri_client/third_party/nanopb/CMakeLists.txt | 103 -- fri_client/third_party/nanopb/LICENSE.txt | 20 - fri_client/third_party/nanopb/README.txt | 61 - .../nanopb/cmake/NanoPBConfig.cmake.in | 10 - .../third_party/nanopb/include/nanopb/pb.h | 519 ------- .../nanopb/include/nanopb/pb_decode.h | 149 -- .../nanopb/include/nanopb/pb_encode.h | 154 --- .../nanopb/include/nanopb/pb_syshdr.h | 127 -- .../nanopb/include/nanopb/pb_syshdr_win.h | 119 -- fri_client/third_party/nanopb/src/pb_decode.c | 1198 ----------------- fri_client/third_party/nanopb/src/pb_encode.c | 671 --------- 20 files changed, 39 insertions(+), 3349 deletions(-) delete mode 100644 fri_client/third_party/nanopb/.gitignore delete mode 100644 fri_client/third_party/nanopb/CHANGELOG.txt delete mode 100644 fri_client/third_party/nanopb/CMakeLists.txt delete mode 100644 fri_client/third_party/nanopb/LICENSE.txt delete mode 100644 fri_client/third_party/nanopb/README.txt delete mode 100644 fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in delete mode 100644 fri_client/third_party/nanopb/include/nanopb/pb.h delete mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_decode.h delete mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_encode.h delete mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h delete mode 100644 fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h delete mode 100644 fri_client/third_party/nanopb/src/pb_decode.c delete mode 100644 fri_client/third_party/nanopb/src/pb_encode.c diff --git a/fri_client/CMakeLists.txt b/fri_client/CMakeLists.txt index 1ee57cde..eccbf7ac 100644 --- a/fri_client/CMakeLists.txt +++ b/fri_client/CMakeLists.txt @@ -16,14 +16,11 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() find_package(ament_cmake REQUIRED) +find_package(nanopb REQUIRED) ### Append CMAKE_MODULE_PATH by custom find file list(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_SOURCE_DIR}/cmake) -### Third party dependency -add_subdirectory(third_party/nanopb) - - include_directories(include src) ### Add the Fast Robot Interface libray @@ -41,30 +38,6 @@ add_library(fri_client SHARED src/pb_frimessages_callbacks.c ) -if(MSVC) - target_compile_options(fri_client - PRIVATE - -DPB_SYSTEM_HEADER= - -DPB_FIELD_16BIT - -DWIN32 - -DHAVE_STDINT_H - -DHAVE_STDBOOL_H - ) -else() - target_compile_options(fri_client - PRIVATE - -O2 - -Wall - -DHAVE_SOCKLEN_T - -DPB_SYSTEM_HEADER= - -DPB_FIELD_16BIT - -DHAVE_STDINT_H - -DHAVE_STDDEF_H - -DHAVE_STDBOOL_H - -DHAVE_STDLIB_H - -DHAVE_STRING_H - ) -endif() file(GLOB private_headers LIST_DIRECTORIES FALSE @@ -76,7 +49,7 @@ file(GLOB private_headers src/pb_frimessages_callbacks.h ) -target_link_libraries(fri_client PRIVATE NanoPB::nanopb) +target_link_libraries(fri_client PRIVATE nanopb) ament_export_targets(fri_client HAS_LIBRARY_TARGET) diff --git a/fri_client/src/FRIMessages.pb.c b/fri_client/src/FRIMessages.pb.c index 6aa13458..4fa7ee2a 100644 --- a/fri_client/src/FRIMessages.pb.c +++ b/fri_client/src/FRIMessages.pb.c @@ -5,35 +5,35 @@ -const pb_field_t JointValues_fields[2] = { +const pb_msgdesc_t JointValues_fields[2] = { PB_FIELD2( 1, DOUBLE , REPEATED, CALLBACK, FIRST, JointValues, value, value, 0), PB_LAST_FIELD }; -const pb_field_t TimeStamp_fields[3] = { +const pb_sm TimeStamp_fields[3] = { PB_FIELD2( 1, UINT32 , REQUIRED, STATIC , FIRST, TimeStamp, sec, sec, 0), PB_FIELD2( 2, UINT32 , REQUIRED, STATIC , OTHER, TimeStamp, nanosec, sec, 0), PB_LAST_FIELD }; -const pb_field_t CartesianVector_fields[2] = { +const pb_msgdesc_t CartesianVector_fields[2] = { PB_FIELD2( 1, DOUBLE , REPEATED, STATIC , FIRST, CartesianVector, element, element, 0), PB_LAST_FIELD }; -const pb_field_t Checksum_fields[2] = { +const pb_msgdesc_t Checksum_fields[2] = { PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, Checksum, crc32, crc32, 0), PB_LAST_FIELD }; -const pb_field_t Transformation_fields[4] = { +const pb_msgdesc_t Transformation_fields[4] = { PB_FIELD2( 1, STRING , REQUIRED, STATIC , FIRST, Transformation, name, name, 0), PB_FIELD2( 2, DOUBLE , REPEATED, STATIC , OTHER, Transformation, matrix, name, 0), PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, Transformation, timestamp, matrix, &TimeStamp_fields), PB_LAST_FIELD }; -const pb_field_t FriIOValue_fields[6] = { +const pb_msgdesc_t FriIOValue_fields[6] = { PB_FIELD2( 1, STRING , REQUIRED, STATIC , FIRST, FriIOValue, name, name, 0), PB_FIELD2( 2, ENUM , REQUIRED, STATIC , OTHER, FriIOValue, type, name, 0), PB_FIELD2( 3, ENUM , REQUIRED, STATIC , OTHER, FriIOValue, direction, type, 0), @@ -42,14 +42,14 @@ const pb_field_t FriIOValue_fields[6] = { PB_LAST_FIELD }; -const pb_field_t MessageHeader_fields[4] = { +const pb_msgdesc_t MessageHeader_fields[4] = { PB_FIELD2( 1, UINT32 , REQUIRED, STATIC , FIRST, MessageHeader, messageIdentifier, messageIdentifier, 0), PB_FIELD2( 2, UINT32 , REQUIRED, STATIC , OTHER, MessageHeader, sequenceCounter, messageIdentifier, 0), PB_FIELD2( 3, UINT32 , REQUIRED, STATIC , OTHER, MessageHeader, reflectedSequenceCounter, sequenceCounter, 0), PB_LAST_FIELD }; -const pb_field_t ConnectionInfo_fields[5] = { +const pb_msgdesc_t ConnectionInfo_fields[5] = { PB_FIELD2( 1, ENUM , REQUIRED, STATIC , FIRST, ConnectionInfo, sessionState, sessionState, 0), PB_FIELD2( 2, ENUM , REQUIRED, STATIC , OTHER, ConnectionInfo, quality, sessionState, 0), PB_FIELD2( 3, UINT32 , OPTIONAL, STATIC , OTHER, ConnectionInfo, sendPeriod, quality, 0), @@ -57,7 +57,7 @@ const pb_field_t ConnectionInfo_fields[5] = { PB_LAST_FIELD }; -const pb_field_t RobotInfo_fields[6] = { +const pb_msgdesc_t RobotInfo_fields[6] = { PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, RobotInfo, numberOfJoints, numberOfJoints, 0), PB_FIELD2( 2, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, safetyState, numberOfJoints, 0), PB_FIELD2( 5, ENUM , REPEATED, CALLBACK, OTHER, RobotInfo, driveState, safetyState, 0), @@ -66,7 +66,7 @@ const pb_field_t RobotInfo_fields[6] = { PB_LAST_FIELD }; -const pb_field_t MessageMonitorData_fields[8] = { +const pb_msgdesc_t MessageMonitorData_fields[8] = { PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageMonitorData, measuredJointPosition, measuredJointPosition, &JointValues_fields), PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, measuredTorque, measuredJointPosition, &JointValues_fields), PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, commandedJointPosition, measuredTorque, &JointValues_fields), @@ -77,7 +77,7 @@ const pb_field_t MessageMonitorData_fields[8] = { PB_LAST_FIELD }; -const pb_field_t MessageIpoData_fields[5] = { +const pb_msgdesc_t MessageIpoData_fields[5] = { PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageIpoData, jointPosition, jointPosition, &JointValues_fields), PB_FIELD2( 10, ENUM , OPTIONAL, STATIC , OTHER, MessageIpoData, clientCommandMode, jointPosition, 0), PB_FIELD2( 11, ENUM , OPTIONAL, STATIC , OTHER, MessageIpoData, overlayType, clientCommandMode, 0), @@ -85,7 +85,7 @@ const pb_field_t MessageIpoData_fields[5] = { PB_LAST_FIELD }; -const pb_field_t MessageCommandData_fields[6] = { +const pb_msgdesc_t MessageCommandData_fields[6] = { PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageCommandData, jointPosition, jointPosition, &JointValues_fields), PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageCommandData, cartesianWrenchFeedForward, jointPosition, &CartesianVector_fields), PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, MessageCommandData, jointTorque, cartesianWrenchFeedForward, &JointValues_fields), @@ -94,13 +94,13 @@ const pb_field_t MessageCommandData_fields[6] = { PB_LAST_FIELD }; -const pb_field_t MessageEndOf_fields[3] = { +const pb_msgdesc_t MessageEndOf_fields[3] = { PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, MessageEndOf, messageLength, messageLength, 0), PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageEndOf, messageChecksum, messageLength, &Checksum_fields), PB_LAST_FIELD }; -const pb_field_t FRIMonitoringMessage_fields[8] = { +const pb_msgdesc_t FRIMonitoringMessage_fields[8] = { PB_FIELD2( 1, MESSAGE , REQUIRED, STATIC , FIRST, FRIMonitoringMessage, header, header, &MessageHeader_fields), PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, robotInfo, header, &RobotInfo_fields), PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, monitorData, robotInfo, &MessageMonitorData_fields), @@ -111,7 +111,7 @@ const pb_field_t FRIMonitoringMessage_fields[8] = { PB_LAST_FIELD }; -const pb_field_t FRICommandMessage_fields[4] = { +const pb_msgdesc_t FRICommandMessage_fields[4] = { PB_FIELD2( 1, MESSAGE , REQUIRED, STATIC , FIRST, FRICommandMessage, header, header, &MessageHeader_fields), PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, FRICommandMessage, commandData, header, &MessageCommandData_fields), PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, FRICommandMessage, endOfMessageData, commandData, &MessageEndOf_fields), @@ -119,7 +119,7 @@ const pb_field_t FRICommandMessage_fields[4] = { }; -/* Check that field information fits in pb_field_t */ +/* Check that field information fits in pb_msgdesc_t */ #if !defined(PB_FIELD_32BIT) /* If you get an error here, it means that you need to define PB_FIELD_32BIT * compile-time option. You can do that in pb.h or on compiler command line. diff --git a/fri_client/src/FRIMessages.pb.h b/fri_client/src/FRIMessages.pb.h index 982abca1..8c3344a7 100644 --- a/fri_client/src/FRIMessages.pb.h +++ b/fri_client/src/FRIMessages.pb.h @@ -3,7 +3,7 @@ #ifndef _PB_FRIMESSAGES_PB_H_ #define _PB_FRIMESSAGES_PB_H_ -#include +#include #ifdef __cplusplus extern "C" { @@ -270,21 +270,21 @@ typedef struct _FRICommandMessage { #define FRICommandMessage_endOfMessageData_tag 15 /* Struct field encoding specification for nanopb */ -extern const pb_field_t JointValues_fields[2]; -extern const pb_field_t TimeStamp_fields[3]; -extern const pb_field_t CartesianVector_fields[2]; -extern const pb_field_t Checksum_fields[2]; -extern const pb_field_t Transformation_fields[4]; -extern const pb_field_t FriIOValue_fields[6]; -extern const pb_field_t MessageHeader_fields[4]; -extern const pb_field_t ConnectionInfo_fields[5]; -extern const pb_field_t RobotInfo_fields[6]; -extern const pb_field_t MessageMonitorData_fields[8]; -extern const pb_field_t MessageIpoData_fields[5]; -extern const pb_field_t MessageCommandData_fields[6]; -extern const pb_field_t MessageEndOf_fields[3]; -extern const pb_field_t FRIMonitoringMessage_fields[8]; -extern const pb_field_t FRICommandMessage_fields[4]; +extern const pb_msgdesc_t JointValues_fields[2]; +extern const pb_msgdesc_t TimeStamp_fields[3]; +extern const pb_msgdesc_t CartesianVector_fields[2]; +extern const pb_msgdesc_t Checksum_fields[2]; +extern const pb_msgdesc_t Transformation_fields[4]; +extern const pb_msgdesc_t FriIOValue_fields[6]; +extern const pb_msgdesc_t MessageHeader_fields[4]; +extern const pb_msgdesc_t ConnectionInfo_fields[5]; +extern const pb_msgdesc_t RobotInfo_fields[6]; +extern const pb_msgdesc_t MessageMonitorData_fields[8]; +extern const pb_msgdesc_t MessageIpoData_fields[5]; +extern const pb_msgdesc_t MessageCommandData_fields[6]; +extern const pb_msgdesc_t MessageEndOf_fields[3]; +extern const pb_msgdesc_t FRIMonitoringMessage_fields[8]; +extern const pb_msgdesc_t FRICommandMessage_fields[4]; /* Maximum encoded size of messages (where known) */ #define TimeStamp_size 12 diff --git a/fri_client/src/friCommandMessageEncoder.cpp b/fri_client/src/friCommandMessageEncoder.cpp index e6888b72..0f8ab361 100644 --- a/fri_client/src/friCommandMessageEncoder.cpp +++ b/fri_client/src/friCommandMessageEncoder.cpp @@ -59,7 +59,7 @@ cost of any service and repair. */ #include #include -#include +#include using namespace KUKA::FRI; diff --git a/fri_client/src/friMonitoringMessageDecoder.cpp b/fri_client/src/friMonitoringMessageDecoder.cpp index fff80995..0787bbdf 100644 --- a/fri_client/src/friMonitoringMessageDecoder.cpp +++ b/fri_client/src/friMonitoringMessageDecoder.cpp @@ -59,7 +59,7 @@ cost of any service and repair. */ #include #include -#include +#include using namespace KUKA::FRI; diff --git a/fri_client/src/pb_frimessages_callbacks.c b/fri_client/src/pb_frimessages_callbacks.c index 16e29b83..244e588f 100644 --- a/fri_client/src/pb_frimessages_callbacks.c +++ b/fri_client/src/pb_frimessages_callbacks.c @@ -62,8 +62,8 @@ cost of any service and repair. #include #include -#include -#include +#include +#include bool encode_repeatedDouble(pb_ostream_t *stream, const pb_field_t *field, void * const *arg) { diff --git a/fri_client/src/pb_frimessages_callbacks.h b/fri_client/src/pb_frimessages_callbacks.h index f31526c3..d72fade3 100644 --- a/fri_client/src/pb_frimessages_callbacks.h +++ b/fri_client/src/pb_frimessages_callbacks.h @@ -64,7 +64,7 @@ cost of any service and repair. extern "C" { #endif -#include +#include #include /** container for repeated double elements */ diff --git a/fri_client/third_party/nanopb/.gitignore b/fri_client/third_party/nanopb/.gitignore deleted file mode 100644 index c0df4621..00000000 --- a/fri_client/third_party/nanopb/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -### build -build diff --git a/fri_client/third_party/nanopb/CHANGELOG.txt b/fri_client/third_party/nanopb/CHANGELOG.txt deleted file mode 100644 index e35ee3ab..00000000 --- a/fri_client/third_party/nanopb/CHANGELOG.txt +++ /dev/null @@ -1,150 +0,0 @@ -nanopb-0.2.8 (2014-05-20) - Fix security issue with PB_ENABLE_MALLOC. (issue 117) - Add option to not add timestamps to .pb.h and .pb.c preambles. (issue 115) - Documentation updates - Improved tests - -nanopb-0.2.7 (2014-04-07) - Fix bug with default values for extension fields (issue 111) - Fix some MISRA-C warnings (issue 91) - Implemented optional malloc() support (issue 80) - Changed pointer-type bytes field datatype - Add a "found" field to pb_extension_t (issue 112) - Add convenience function pb_get_encoded_size() (issue 16) - -nanopb-0.2.6 (2014-02-15) - Fix generator error with bytes callback fields (issue 99) - Fix warnings about large integer constants (issue 102) - Add comments to where STATIC_ASSERT is used (issue 96) - Add warning about unknown field names on .options (issue 105) - Move descriptor.proto to google/protobuf subdirectory (issue 104) - Improved tests - -nanopb-0.2.5 (2014-01-01) - Fix a bug with encoding negative values in int32 fields (issue 97) - Create binary packages of the generator + dependencies (issue 47) - Add support for pointer-type fields to the encoder (part of issue 80) - Fixed path in FindNanopb.cmake (issue 94) - Improved tests - -nanopb-0.2.4 (2013-11-07) - Remove the deprecated NANOPB_INTERNALS functions from public API. - Document the security model. - Check array and bytes max sizes when encoding (issue 90) - Add #defines for maximum encoded message size (issue 89) - Add #define tags for extension fields (issue 93) - Fix MISRA C violations (issue 91) - Clean up pb_field_t definition with typedefs. - -nanopb-0.2.3 (2013-09-18) - Improve compatibility by removing ternary operator from initializations (issue 88) - Fix build error on Visual C++ (issue 84, patch by Markus Schwarzenberg) - Don't stop on unsupported extension fields (issue 83) - Add an example pb_syshdr.h file for non-C99 compilers - Reorganize tests and examples into subfolders (issue 63) - Switch from Makefiles to scons for building the tests - Make the tests buildable on Windows - -nanopb-0.2.2 (2013-08-18) - Add support for extension fields (issue 17) - Fix unknown fields in empty message (issue 78) - Include the field tags in the generated .pb.h file. - Add pb_decode_delimited and pb_encode_delimited wrapper functions (issue 74) - Add a section in top of pb.h for changing compilation settings (issue 76) - Documentation improvements (issues 12, 77 and others) - Improved tests - -nanopb-0.2.1 (2013-04-14) - NOTE: The default callback function signature has changed. - If you don't want to update your code, define PB_OLD_CALLBACK_STYLE. - - Change the callback function to use void** (issue 69) - Add support for defining the nanopb options in a separate file (issue 12) - Add support for packed structs in IAR and MSVC (in addition to GCC) (issue 66) - Implement error message support for the encoder side (issue 7) - Handle unterminated strings when encoding (issue 68) - Fix bug with empty strings in repeated string callbacks (issue 73) - Fix regression in 0.2.0 with optional callback fields (issue 70) - Fix bugs with empty message types (issues 64, 65) - Fix some compiler warnings on clang (issue 67) - Some portability improvements (issues 60, 62) - Various new generator options - Improved tests - -nanopb-0.2.0 (2013-03-02) - NOTE: This release requires you to regenerate all .pb.c - files. Files generated by older versions will not - compile anymore. - - Reformat generated .pb.c files using macros (issue 58) - Rename PB_HTYPE_ARRAY -> PB_HTYPE_REPEATED - Separate PB_HTYPE to PB_ATYPE and PB_HTYPE - Move STATIC_ASSERTs to .pb.c file - Added CMake file (by Pavel Ilin) - Add option to give file extension to generator (by Michael Haberler) - Documentation updates - -nanopb-0.1.9 (2013-02-13) - Fixed error message bugs (issues 52, 56) - Sanitize #ifndef filename (issue 50) - Performance improvements - Add compile-time option PB_BUFFER_ONLY - Add Java package name to nanopb.proto - Check for sizeof(double) == 8 (issue 54) - Added generator option to ignore some fields. (issue 51) - Added generator option to make message structs packed. (issue 49) - Add more test cases. - -nanopb-0.1.8 (2012-12-13) - Fix bugs in the enum short names introduced in 0.1.7 (issues 42, 43) - Fix STATIC_ASSERT macro when using multiple .proto files. (issue 41) - Fix missing initialization of istream.errmsg - Make tests/Makefile work for non-gcc compilers (issue 40) - -nanopb-0.1.7 (2012-11-11) - Remove "skip" mode from pb_istream_t callbacks. Example implementation had a bug. (issue 37) - Add option to use shorter names for enum values (issue 38) - Improve options support in generator (issues 12, 30) - Add nanopb version number to generated files (issue 36) - Add extern "C" to generated headers (issue 35) - Add names for structs to allow forward declaration (issue 39) - Add buffer size check in example (issue 34) - Fix build warnings on MS compilers (issue 33) - -nanopb-0.1.6 (2012-09-02) - Reorganize the field decoder interface (issue 2) - Improve performance in submessage decoding (issue 28) - Implement error messages in the decoder side (issue 7) - Extended testcases (alltypes test is now complete). - Fix some compiler warnings (issues 25, 26, 27, 32). - -nanopb-0.1.5 (2012-08-04) - Fix bug in decoder with packed arrays (issue 23). - Extended testcases. - Fix some compiler warnings. - -nanopb-0.1.4 (2012-07-05) - Add compile-time options for easy-to-use >255 field support. - Improve the detection of missing required fields. - Added example on how to handle union messages. - Fix generator error with .proto without messages. - Fix problems that stopped the code from compiling with some compilers. - Fix some compiler warnings. - -nanopb-0.1.3 (2012-06-12) - Refactor the field encoder interface. - Improve generator error messages (issue 5) - Add descriptor.proto into the #include exclusion list - Fix some compiler warnings. - -nanopb-0.1.2 (2012-02-15) - Make the generator to generate include for other .proto files (issue 4). - Fixed generator not working on Windows (issue 3) - -nanopb-0.1.1 (2012-01-14) - Fixed bug in encoder with 'bytes' fields (issue 1). - Fixed a bug in the generator that caused a compiler error on sfixed32 and sfixed64 fields. - Extended testcases. - -nanopb-0.1.0 (2012-01-06) - First stable release. diff --git a/fri_client/third_party/nanopb/CMakeLists.txt b/fri_client/third_party/nanopb/CMakeLists.txt deleted file mode 100644 index fd4a64de..00000000 --- a/fri_client/third_party/nanopb/CMakeLists.txt +++ /dev/null @@ -1,103 +0,0 @@ -cmake_minimum_required(VERSION 3.1...3.15) - -### CMake support for the nanopb library - protocol buffers for embedded systems -if(${CMAKE_VERSION} VERSION_LESS 3.12) - cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) -endif() - -project(NanoPB VERSION 0.2.8 - DESCRIPTION "Nanopb - Protocol Buffers for Embedded Systems." - LANGUAGES C -) - -### Append CMAKE_MODULE_PATH by custom find file -list(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_SOURCE_DIR}/cmake) - -### Add the nanopb library -add_library(nanopb - src/pb_decode.c - src/pb_encode.c -) - -### Add compile options, similar to https://stackoverflow.com/questions/45955272/modern-way-to-set-compiler-flags-in-cross-platform-cmake-project -if(MSVC) - target_compile_options(nanopb - PRIVATE - -DPB_SYSTEM_HEADER= - -DPB_FIELD_16BIT - -DWIN32 - -DHAVE_STDINT_H - -DHAVE_STDBOOL_H - ) -else() - target_compile_options(nanopb - PRIVATE - -O2 - -Wall - -DHAVE_SOCKLEN_T - -DPB_SYSTEM_HEADER= - -DPB_FIELD_16BIT - -DHAVE_STDINT_H - -DHAVE_STDDEF_H - -DHAVE_STDBOOL_H - -DHAVE_STDLIB_H - -DHAVE_STRING_H - ) -endif() - -### Create an alias so that one can link against this library inside build tree -add_library(NanoPB::nanopb ALIAS nanopb) - -### Set target properties -target_include_directories(nanopb - PUBLIC - $ - $ -) - -### Install instructions -include(GNUInstallDirs) -set(INSTALL_CONFIGDIR ${CMAKE_INSTALL_LIBDIR}/cmake/nanopb) - -install(TARGETS nanopb - EXPORT nanopb-targets - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} -) - -### Set exported target's name to NanoPB -set_target_properties(nanopb PROPERTIES EXPORT_NAME NanoPB) -install(DIRECTORY include/ DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}) - -### Export target to a script -install(EXPORT nanopb-targets - FILE NanoPBTargets.cmake - NAMESPACE NanoPB:: - DESTINATION ${INSTALL_CONFIGDIR} -) - -### Create a ConfigVersion.cmake file -include(CMakePackageConfigHelpers) -write_basic_package_version_file( - ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfigVersion.cmake - VERSION ${PROJECT_VERSION} - COMPATIBILITY AnyNewerVersion -) - -configure_package_config_file(${CMAKE_CURRENT_LIST_DIR}/cmake/NanoPBConfig.cmake.in - ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfig.cmake - INSTALL_DESTINATION ${INSTALL_CONFIGDIR} -) - -### Install the config, configversion and custom find modules -install(FILES - ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfig.cmake - ${CMAKE_CURRENT_BINARY_DIR}/NanoPBConfigVersion.cmake - DESTINATION ${INSTALL_CONFIGDIR} -) - -### Export target from the build tree -export(EXPORT nanopb-targets FILE ${CMAKE_CURRENT_BINARY_DIR}/NanoPBTargets.cmake NAMESPACE NanoPB) - -### Register package in user's package registry -export(PACKAGE NanoPB) \ No newline at end of file diff --git a/fri_client/third_party/nanopb/LICENSE.txt b/fri_client/third_party/nanopb/LICENSE.txt deleted file mode 100644 index d11c9af1..00000000 --- a/fri_client/third_party/nanopb/LICENSE.txt +++ /dev/null @@ -1,20 +0,0 @@ -Copyright (c) 2011 Petteri Aimonen - -This software is provided 'as-is', without any express or -implied warranty. In no event will the authors be held liable -for any damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you - must not claim that you wrote the original software. If you use - this software in a product, an acknowledgment in the product - documentation would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and - must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source - distribution. diff --git a/fri_client/third_party/nanopb/README.txt b/fri_client/third_party/nanopb/README.txt deleted file mode 100644 index 0f2ade8b..00000000 --- a/fri_client/third_party/nanopb/README.txt +++ /dev/null @@ -1,61 +0,0 @@ -Nanopb is a small code-size Protocol Buffers implementation in ansi C. It is -especially suitable for use in microcontrollers, but fits any memory -restricted system. - -Homepage: http://kapsi.fi/~jpa/nanopb/ - - - - -Using the nanopb library -======================== -To use the nanopb library, you need to do two things: - -1) Compile your .proto files for nanopb, using protoc. -2) Include pb_encode.c and pb_decode.c in your project. - -The easiest way to get started is to study the project in "examples/simple". -It contains a Makefile, which should work directly under most Linux systems. -However, for any other kind of build system, see the manual steps in -README.txt in that folder. - - - -Using the Protocol Buffers compiler (protoc) -============================================ -The nanopb generator is implemented as a plugin for the Google's own protoc -compiler. This has the advantage that there is no need to reimplement the -basic parsing of .proto files. However, it does mean that you need the -Google's protobuf library in order to run the generator. - -If you have downloaded a binary package for nanopb (either Windows, Linux or -Mac OS X version), the 'protoc' binary is included in the 'generator-bin' -folder. In this case, you are ready to go. Simply run this command: - - generator-bin/protoc --nanopb_out=. myprotocol.proto - -However, if you are using a git checkout or a plain source distribution, you -need to provide your own version of protoc and the Google's protobuf library. -On Linux, the necessary packages are protobuf-compiler and python-protobuf. -On Windows, you can either build Google's protobuf library from source or use -one of the binary distributions of it. In either case, if you use a separate -protoc, you need to manually give the path to nanopb generator: - - protoc --plugin=protoc-gen-nanopb=nanopb/generator/protoc-gen-nanopb ... - - - -Running the tests -================= -If you want to perform further development of the nanopb core, or to verify -its functionality using your compiler and platform, you'll want to run the -test suite. The build rules for the test suite are implemented using Scons, -so you need to have that installed. To run the tests: - - cd tests - scons - -This will show the progress of various test cases. If the output does not -end in an error, the test cases were successful. - - diff --git a/fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in b/fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in deleted file mode 100644 index 245eb7c0..00000000 --- a/fri_client/third_party/nanopb/cmake/NanoPBConfig.cmake.in +++ /dev/null @@ -1,10 +0,0 @@ -get_filename_component(NanoPB_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) -include(CMakeFindDependencyMacro) - -list(APPEND CMAKE_MODULE_PATH ${NanoPB_CMAKE_DIR}) - -if(NOT TARGET NanoPB::NanoPB) - include("${NanoPB_CMAKE_DIR}/NanoPBTargets.cmake") -endif() - -set(NanoPB_LIBRARIES NanoPB::NanoPB) \ No newline at end of file diff --git a/fri_client/third_party/nanopb/include/nanopb/pb.h b/fri_client/third_party/nanopb/include/nanopb/pb.h deleted file mode 100644 index 258ec925..00000000 --- a/fri_client/third_party/nanopb/include/nanopb/pb.h +++ /dev/null @@ -1,519 +0,0 @@ -/* Common parts of the nanopb library. Most of these are quite low-level - * stuff. For the high-level interface, see pb_encode.h and pb_decode.h. - */ - -#ifndef _PB_H_ -#define _PB_H_ - -/***************************************************************** - * Nanopb compilation time options. You can change these here by * - * uncommenting the lines, or on the compiler command line. * - *****************************************************************/ - -/* Enable support for dynamically allocated fields */ -/* #define PB_ENABLE_MALLOC 1 */ - -/* Define this if your CPU architecture is big endian, i.e. it - * stores the most-significant byte first. */ -/* #define __BIG_ENDIAN__ 1 */ - -/* Increase the number of required fields that are tracked. - * A compiler warning will tell if you need this. */ -/* #define PB_MAX_REQUIRED_FIELDS 256 */ - -/* Add support for tag numbers > 255 and fields larger than 255 bytes. */ -/* #define PB_FIELD_16BIT 1 */ - -/* Add support for tag numbers > 65536 and fields larger than 65536 bytes. */ -/* #define PB_FIELD_32BIT 1 */ - -/* Disable support for error messages in order to save some code space. */ -/* #define PB_NO_ERRMSG 1 */ - -/* Disable support for custom streams (support only memory buffers). */ -/* #define PB_BUFFER_ONLY 1 */ - -/* Switch back to the old-style callback function signature. - * This was the default until nanopb-0.2.1. */ -/* #define PB_OLD_CALLBACK_STYLE */ - - -/****************************************************************** - * You usually don't need to change anything below this line. * - * Feel free to look around and use the defined macros, though. * - ******************************************************************/ - - -/* Version of the nanopb library. Just in case you want to check it in - * your own program. */ -#define NANOPB_VERSION nanopb-0.2.8 - -/* Include all the system headers needed by nanopb. You will need the - * definitions of the following: - * - strlen, memcpy, memset functions - * - [u]int8_t, [u]int16_t, [u]int32_t, [u]int64_t - * - size_t - * - bool - * - * If you don't have the standard header files, you can instead provide - * a custom header that defines or includes all this. In that case, - * define PB_SYSTEM_HEADER to the path of this file. - */ -#ifdef PB_SYSTEM_HEADER -#include PB_SYSTEM_HEADER -#else -#include -#include -#include -#include - -#ifdef PB_ENABLE_MALLOC -#include -#endif -#endif - -/* Macro for defining packed structures (compiler dependent). - * This just reduces memory requirements, but is not required. - */ -#if defined(__GNUC__) || defined(__clang__) - /* For GCC and clang */ -# define PB_PACKED_STRUCT_START -# define PB_PACKED_STRUCT_END -# define pb_packed __attribute__((packed)) -#elif defined(__ICCARM__) - /* For IAR ARM compiler */ -# define PB_PACKED_STRUCT_START _Pragma("pack(push, 1)") -# define PB_PACKED_STRUCT_END _Pragma("pack(pop)") -# define pb_packed -#elif defined(_MSC_VER) && (_MSC_VER >= 1500) - /* For Microsoft Visual C++ */ -# define PB_PACKED_STRUCT_START __pragma(pack(push, 1)) -# define PB_PACKED_STRUCT_END __pragma(pack(pop)) -# define pb_packed -#else - /* Unknown compiler */ -# define PB_PACKED_STRUCT_START -# define PB_PACKED_STRUCT_END -# define pb_packed -#endif - -/* Handly macro for suppressing unreferenced-parameter compiler warnings. */ -#ifndef UNUSED -#define UNUSED(x) (void)(x) -#endif - -/* Compile-time assertion, used for checking compatible compilation options. - * If this does not work properly on your compiler, use #define STATIC_ASSERT - * to disable it. - * - * But before doing that, check carefully the error message / place where it - * comes from to see if the error has a real cause. Unfortunately the error - * message is not always very clear to read, but you can see the reason better - * in the place where the STATIC_ASSERT macro was called. - */ -#ifndef STATIC_ASSERT -#define STATIC_ASSERT(COND,MSG) typedef char STATIC_ASSERT_MSG(MSG, __LINE__, __COUNTER__)[(COND)?1:-1]; -#define STATIC_ASSERT_MSG(MSG, LINE, COUNTER) STATIC_ASSERT_MSG_(MSG, LINE, COUNTER) -#define STATIC_ASSERT_MSG_(MSG, LINE, COUNTER) static_assertion_##MSG##LINE##COUNTER -#endif - -/* Number of required fields to keep track of. */ -#ifndef PB_MAX_REQUIRED_FIELDS -#define PB_MAX_REQUIRED_FIELDS 64 -#endif - -#if PB_MAX_REQUIRED_FIELDS < 64 -#error You should not lower PB_MAX_REQUIRED_FIELDS from the default value (64). -#endif - -/* List of possible field types. These are used in the autogenerated code. - * Least-significant 4 bits tell the scalar type - * Most-significant 4 bits specify repeated/required/packed etc. - */ - -typedef uint8_t pb_type_t; - -/**** Field data types ****/ - -/* Numeric types */ -#define PB_LTYPE_VARINT 0x00 /* int32, int64, enum, bool */ -#define PB_LTYPE_UVARINT 0x01 /* uint32, uint64 */ -#define PB_LTYPE_SVARINT 0x02 /* sint32, sint64 */ -#define PB_LTYPE_FIXED32 0x03 /* fixed32, sfixed32, float */ -#define PB_LTYPE_FIXED64 0x04 /* fixed64, sfixed64, double */ - -/* Marker for last packable field type. */ -#define PB_LTYPE_LAST_PACKABLE 0x04 - -/* Byte array with pre-allocated buffer. - * data_size is the length of the allocated PB_BYTES_ARRAY structure. */ -#define PB_LTYPE_BYTES 0x05 - -/* String with pre-allocated buffer. - * data_size is the maximum length. */ -#define PB_LTYPE_STRING 0x06 - -/* Submessage - * submsg_fields is pointer to field descriptions */ -#define PB_LTYPE_SUBMESSAGE 0x07 - -/* Extension pseudo-field - * The field contains a pointer to pb_extension_t */ -#define PB_LTYPE_EXTENSION 0x08 - -/* Number of declared LTYPES */ -#define PB_LTYPES_COUNT 9 -#define PB_LTYPE_MASK 0x0F - -/**** Field repetition rules ****/ - -#define PB_HTYPE_REQUIRED 0x00 -#define PB_HTYPE_OPTIONAL 0x10 -#define PB_HTYPE_REPEATED 0x20 -#define PB_HTYPE_MASK 0x30 - -/**** Field allocation types ****/ - -#define PB_ATYPE_STATIC 0x00 -#define PB_ATYPE_POINTER 0x80 -#define PB_ATYPE_CALLBACK 0x40 -#define PB_ATYPE_MASK 0xC0 - -#define PB_ATYPE(x) ((x) & PB_ATYPE_MASK) -#define PB_HTYPE(x) ((x) & PB_HTYPE_MASK) -#define PB_LTYPE(x) ((x) & PB_LTYPE_MASK) - -/* Data type used for storing sizes of struct fields - * and array counts. - */ -#if defined(PB_FIELD_32BIT) - typedef uint32_t pb_size_t; - typedef int32_t pb_ssize_t; -#elif defined(PB_FIELD_16BIT) - typedef uint16_t pb_size_t; - typedef int16_t pb_ssize_t; -#else - typedef uint8_t pb_size_t; - typedef int8_t pb_ssize_t; -#endif - -/* This structure is used in auto-generated constants - * to specify struct fields. - * You can change field sizes if you need structures - * larger than 256 bytes or field tags larger than 256. - * The compiler should complain if your .proto has such - * structures. Fix that by defining PB_FIELD_16BIT or - * PB_FIELD_32BIT. - */ -PB_PACKED_STRUCT_START -typedef struct _pb_field_t pb_field_t; -struct _pb_field_t { - pb_size_t tag; - pb_type_t type; - pb_size_t data_offset; /* Offset of field data, relative to previous field. */ - pb_ssize_t size_offset; /* Offset of array size or has-boolean, relative to data */ - pb_size_t data_size; /* Data size in bytes for a single item */ - pb_size_t array_size; /* Maximum number of entries in array */ - - /* Field definitions for submessage - * OR default value for all other non-array, non-callback types - * If null, then field will zeroed. */ - const void *ptr; -} pb_packed; -PB_PACKED_STRUCT_END - -/* Make sure that the standard integer types are of the expected sizes. - * All kinds of things may break otherwise.. atleast all fixed* types. - * - * If you get errors here, it probably means that your stdint.h is not - * correct for your platform. - */ -STATIC_ASSERT(sizeof(int8_t) == 1, INT8_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(uint8_t) == 1, UINT8_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(int16_t) == 2, INT16_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(uint16_t) == 2, UINT16_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(int32_t) == 4, INT32_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(uint32_t) == 4, UINT32_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(int64_t) == 8, INT64_T_WRONG_SIZE) -STATIC_ASSERT(sizeof(uint64_t) == 8, UINT64_T_WRONG_SIZE) - -/* This structure is used for 'bytes' arrays. - * It has the number of bytes in the beginning, and after that an array. - * Note that actual structs used will have a different length of bytes array. - */ -#define PB_BYTES_ARRAY_T(n) struct { size_t size; uint8_t bytes[n]; } -#define PB_BYTES_ARRAY_T_ALLOCSIZE(n) ((size_t)n + offsetof(pb_bytes_array_t, bytes)) - -struct _pb_bytes_array_t { - size_t size; - uint8_t bytes[1]; -}; -typedef struct _pb_bytes_array_t pb_bytes_array_t; - -/* This structure is used for giving the callback function. - * It is stored in the message structure and filled in by the method that - * calls pb_decode. - * - * The decoding callback will be given a limited-length stream - * If the wire type was string, the length is the length of the string. - * If the wire type was a varint/fixed32/fixed64, the length is the length - * of the actual value. - * The function may be called multiple times (especially for repeated types, - * but also otherwise if the message happens to contain the field multiple - * times.) - * - * The encoding callback will receive the actual output stream. - * It should write all the data in one call, including the field tag and - * wire type. It can write multiple fields. - * - * The callback can be null if you want to skip a field. - */ -typedef struct _pb_istream_t pb_istream_t; -typedef struct _pb_ostream_t pb_ostream_t; -typedef struct _pb_callback_t pb_callback_t; -struct _pb_callback_t { -#ifdef PB_OLD_CALLBACK_STYLE - /* Deprecated since nanopb-0.2.1 */ - union { - bool (*decode)(pb_istream_t *stream, const pb_field_t *field, void *arg); - bool (*encode)(pb_ostream_t *stream, const pb_field_t *field, const void *arg); - } funcs; -#else - /* New function signature, which allows modifying arg contents in callback. */ - union { - bool (*decode)(pb_istream_t *stream, const pb_field_t *field, void **arg); - bool (*encode)(pb_ostream_t *stream, const pb_field_t *field, void * const *arg); - } funcs; -#endif - - /* Free arg for use by callback */ - void *arg; -}; - -/* Wire types. Library user needs these only in encoder callbacks. */ -typedef enum { - PB_WT_VARINT = 0, - PB_WT_64BIT = 1, - PB_WT_STRING = 2, - PB_WT_32BIT = 5 -} pb_wire_type_t; - -/* Structure for defining the handling of unknown/extension fields. - * Usually the pb_extension_type_t structure is automatically generated, - * while the pb_extension_t structure is created by the user. However, - * if you want to catch all unknown fields, you can also create a custom - * pb_extension_type_t with your own callback. - */ -typedef struct _pb_extension_type_t pb_extension_type_t; -typedef struct _pb_extension_t pb_extension_t; -struct _pb_extension_type_t { - /* Called for each unknown field in the message. - * If you handle the field, read off all of its data and return true. - * If you do not handle the field, do not read anything and return true. - * If you run into an error, return false. - * Set to NULL for default handler. - */ - bool (*decode)(pb_istream_t *stream, pb_extension_t *extension, - uint32_t tag, pb_wire_type_t wire_type); - - /* Called once after all regular fields have been encoded. - * If you have something to write, do so and return true. - * If you do not have anything to write, just return true. - * If you run into an error, return false. - * Set to NULL for default handler. - */ - bool (*encode)(pb_ostream_t *stream, const pb_extension_t *extension); - - /* Free field for use by the callback. */ - const void *arg; -}; - -struct _pb_extension_t { - /* Type describing the extension field. Usually you'll initialize - * this to a pointer to the automatically generated structure. */ - const pb_extension_type_t *type; - - /* Destination for the decoded data. This must match the datatype - * of the extension field. */ - void *dest; - - /* Pointer to the next extension handler, or NULL. - * If this extension does not match a field, the next handler is - * automatically called. */ - pb_extension_t *next; - - /* The decoder sets this to true if the extension was found. - * Ignored for encoding. */ - bool found; -}; - -/* Memory allocation functions to use. You can define pb_realloc and - * pb_free to custom functions if you want. */ -#ifdef PB_ENABLE_MALLOC -# ifndef pb_realloc -# define pb_realloc(ptr, size) realloc(ptr, size) -# endif -# ifndef pb_free -# define pb_free(ptr) free(ptr) -# endif -#endif - -/* These macros are used to declare pb_field_t's in the constant array. */ -/* Size of a structure member, in bytes. */ -#define pb_membersize(st, m) (sizeof ((st*)0)->m) -/* Number of entries in an array. */ -#define pb_arraysize(st, m) (pb_membersize(st, m) / pb_membersize(st, m[0])) -/* Delta from start of one member to the start of another member. */ -#define pb_delta(st, m1, m2) ((int)offsetof(st, m1) - (int)offsetof(st, m2)) -/* Marks the end of the field list */ -#define PB_LAST_FIELD {0,(pb_type_t) 0,0,0,0,0,0} - -/* Macros for filling in the data_offset field */ -/* data_offset for first field in a message */ -#define PB_DATAOFFSET_FIRST(st, m1, m2) (offsetof(st, m1)) -/* data_offset for subsequent fields */ -#define PB_DATAOFFSET_OTHER(st, m1, m2) (offsetof(st, m1) - offsetof(st, m2) - pb_membersize(st, m2)) -/* Choose first/other based on m1 == m2 (deprecated, remains for backwards compatibility) */ -#define PB_DATAOFFSET_CHOOSE(st, m1, m2) (int)(offsetof(st, m1) == offsetof(st, m2) \ - ? PB_DATAOFFSET_FIRST(st, m1, m2) \ - : PB_DATAOFFSET_OTHER(st, m1, m2)) - -/* Required fields are the simplest. They just have delta (padding) from - * previous field end, and the size of the field. Pointer is used for - * submessages and default values. - */ -#define PB_REQUIRED_STATIC(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_STATIC | PB_HTYPE_REQUIRED | ltype, \ - fd, 0, pb_membersize(st, m), 0, ptr} - -/* Optional fields add the delta to the has_ variable. */ -#define PB_OPTIONAL_STATIC(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_STATIC | PB_HTYPE_OPTIONAL | ltype, \ - fd, \ - pb_delta(st, has_ ## m, m), \ - pb_membersize(st, m), 0, ptr} - -/* Repeated fields have a _count field and also the maximum number of entries. */ -#define PB_REPEATED_STATIC(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_STATIC | PB_HTYPE_REPEATED | ltype, \ - fd, \ - pb_delta(st, m ## _count, m), \ - pb_membersize(st, m[0]), \ - pb_arraysize(st, m), ptr} - -/* Allocated fields carry the size of the actual data, not the pointer */ -#define PB_REQUIRED_POINTER(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_POINTER | PB_HTYPE_REQUIRED | ltype, \ - fd, 0, pb_membersize(st, m[0]), 0, ptr} - -/* Optional fields don't need a has_ variable, as information would be redundant */ -#define PB_OPTIONAL_POINTER(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_POINTER | PB_HTYPE_OPTIONAL | ltype, \ - fd, 0, pb_membersize(st, m[0]), 0, ptr} - -/* Repeated fields have a _count field and a pointer to array of pointers */ -#define PB_REPEATED_POINTER(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_POINTER | PB_HTYPE_REPEATED | ltype, \ - fd, pb_delta(st, m ## _count, m), \ - pb_membersize(st, m[0]), 0, ptr} - -/* Callbacks are much like required fields except with special datatype. */ -#define PB_REQUIRED_CALLBACK(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_CALLBACK | PB_HTYPE_REQUIRED | ltype, \ - fd, 0, pb_membersize(st, m), 0, ptr} - -#define PB_OPTIONAL_CALLBACK(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_CALLBACK | PB_HTYPE_OPTIONAL | ltype, \ - fd, 0, pb_membersize(st, m), 0, ptr} - -#define PB_REPEATED_CALLBACK(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_CALLBACK | PB_HTYPE_REPEATED | ltype, \ - fd, 0, pb_membersize(st, m), 0, ptr} - -/* Optional extensions don't have the has_ field, as that would be redundant. */ -#define PB_OPTEXT_STATIC(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_STATIC | PB_HTYPE_OPTIONAL | ltype, \ - 0, \ - 0, \ - pb_membersize(st, m), 0, ptr} - -#define PB_OPTEXT_CALLBACK(tag, st, m, fd, ltype, ptr) \ - {tag, PB_ATYPE_CALLBACK | PB_HTYPE_OPTIONAL | ltype, \ - 0, 0, pb_membersize(st, m), 0, ptr} - -/* The mapping from protobuf types to LTYPEs is done using these macros. */ -#define PB_LTYPE_MAP_BOOL PB_LTYPE_VARINT -#define PB_LTYPE_MAP_BYTES PB_LTYPE_BYTES -#define PB_LTYPE_MAP_DOUBLE PB_LTYPE_FIXED64 -#define PB_LTYPE_MAP_ENUM PB_LTYPE_VARINT -#define PB_LTYPE_MAP_FIXED32 PB_LTYPE_FIXED32 -#define PB_LTYPE_MAP_FIXED64 PB_LTYPE_FIXED64 -#define PB_LTYPE_MAP_FLOAT PB_LTYPE_FIXED32 -#define PB_LTYPE_MAP_INT32 PB_LTYPE_VARINT -#define PB_LTYPE_MAP_INT64 PB_LTYPE_VARINT -#define PB_LTYPE_MAP_MESSAGE PB_LTYPE_SUBMESSAGE -#define PB_LTYPE_MAP_SFIXED32 PB_LTYPE_FIXED32 -#define PB_LTYPE_MAP_SFIXED64 PB_LTYPE_FIXED64 -#define PB_LTYPE_MAP_SINT32 PB_LTYPE_SVARINT -#define PB_LTYPE_MAP_SINT64 PB_LTYPE_SVARINT -#define PB_LTYPE_MAP_STRING PB_LTYPE_STRING -#define PB_LTYPE_MAP_UINT32 PB_LTYPE_UVARINT -#define PB_LTYPE_MAP_UINT64 PB_LTYPE_UVARINT -#define PB_LTYPE_MAP_EXTENSION PB_LTYPE_EXTENSION - -/* This is the actual macro used in field descriptions. - * It takes these arguments: - * - Field tag number - * - Field type: BOOL, BYTES, DOUBLE, ENUM, FIXED32, FIXED64, - * FLOAT, INT32, INT64, MESSAGE, SFIXED32, SFIXED64 - * SINT32, SINT64, STRING, UINT32, UINT64 or EXTENSION - * - Field rules: REQUIRED, OPTIONAL or REPEATED - * - Allocation: STATIC or CALLBACK - * - Message name - * - Field name - * - Previous field name (or field name again for first field) - * - Pointer to default value or submsg fields. - */ - -#define PB_FIELD(tag, type, rules, allocation, message, field, prevfield, ptr) \ - PB_ ## rules ## _ ## allocation(tag, message, field, \ - PB_DATAOFFSET_CHOOSE(message, field, prevfield), \ - PB_LTYPE_MAP_ ## type, ptr) - -/* This is a new version of the macro used by nanopb generator from - * version 0.2.3 onwards. It avoids the use of a ternary expression in - * the initialization, which confused some compilers. - * - * - Placement: FIRST or OTHER, depending on if this is the first field in structure. - * - */ -#define PB_FIELD2(tag, type, rules, allocation, placement, message, field, prevfield, ptr) \ - PB_ ## rules ## _ ## allocation(tag, message, field, \ - PB_DATAOFFSET_ ## placement(message, field, prevfield), \ - PB_LTYPE_MAP_ ## type, ptr) - - -/* These macros are used for giving out error messages. - * They are mostly a debugging aid; the main error information - * is the true/false return value from functions. - * Some code space can be saved by disabling the error - * messages if not used. - */ -#ifdef PB_NO_ERRMSG -#define PB_RETURN_ERROR(stream,msg) \ - do {\ - UNUSED(stream); \ - return false; \ - } while(0) -#define PB_GET_ERROR(stream) "(errmsg disabled)" -#else -#define PB_RETURN_ERROR(stream,msg) \ - do {\ - if ((stream)->errmsg == NULL) \ - (stream)->errmsg = (msg); \ - return false; \ - } while(0) -#define PB_GET_ERROR(stream) ((stream)->errmsg ? (stream)->errmsg : "(none)") -#endif - -#endif diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_decode.h b/fri_client/third_party/nanopb/include/nanopb/pb_decode.h deleted file mode 100644 index 75ca119f..00000000 --- a/fri_client/third_party/nanopb/include/nanopb/pb_decode.h +++ /dev/null @@ -1,149 +0,0 @@ -/* pb_decode.h: Functions to decode protocol buffers. Depends on pb_decode.c. - * The main function is pb_decode. You also need an input stream, and the - * field descriptions created by nanopb_generator.py. - */ - -#ifndef _PB_DECODE_H_ -#define _PB_DECODE_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/* Structure for defining custom input streams. You will need to provide - * a callback function to read the bytes from your storage, which can be - * for example a file or a network socket. - * - * The callback must conform to these rules: - * - * 1) Return false on IO errors. This will cause decoding to abort. - * 2) You can use state to store your own data (e.g. buffer pointer), - * and rely on pb_read to verify that no-body reads past bytes_left. - * 3) Your callback may be used with substreams, in which case bytes_left - * is different than from the main stream. Don't use bytes_left to compute - * any pointers. - */ -struct _pb_istream_t -{ -#ifdef PB_BUFFER_ONLY - /* Callback pointer is not used in buffer-only configuration. - * Having an int pointer here allows binary compatibility but - * gives an error if someone tries to assign callback function. - */ - int *callback; -#else - bool (*callback)(pb_istream_t *stream, uint8_t *buf, size_t count); -#endif - - void *state; /* Free field for use by callback implementation */ - size_t bytes_left; - -#ifndef PB_NO_ERRMSG - const char *errmsg; -#endif -}; - -/*************************** - * Main decoding functions * - ***************************/ - -/* Decode a single protocol buffers message from input stream into a C structure. - * Returns true on success, false on any failure. - * The actual struct pointed to by dest must match the description in fields. - * Callback fields of the destination structure must be initialized by caller. - * All other fields will be initialized by this function. - * - * Example usage: - * MyMessage msg = {}; - * uint8_t buffer[64]; - * pb_istream_t stream; - * - * // ... read some data into buffer ... - * - * stream = pb_istream_from_buffer(buffer, count); - * pb_decode(&stream, MyMessage_fields, &msg); - */ -bool pb_decode(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct); - -/* Same as pb_decode, except does not initialize the destination structure - * to default values. This is slightly faster if you need no default values - * and just do memset(struct, 0, sizeof(struct)) yourself. - * - * This can also be used for 'merging' two messages, i.e. update only the - * fields that exist in the new message. - * - * Note: If this function returns with an error, it will not release any - * dynamically allocated fields. You will need to call pb_release() yourself. - */ -bool pb_decode_noinit(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct); - -/* Same as pb_decode, except expects the stream to start with the message size - * encoded as varint. Corresponds to parseDelimitedFrom() in Google's - * protobuf API. - */ -bool pb_decode_delimited(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct); - -#ifdef PB_ENABLE_MALLOC -/* Release any allocated pointer fields. If you use dynamic allocation, you should - * call this for any successfully decoded message when you are done with it. If - * pb_decode() returns with an error, the message is already released. - */ -void pb_release(const pb_field_t fields[], void *dest_struct); -#endif - - -/************************************** - * Functions for manipulating streams * - **************************************/ - -/* Create an input stream for reading from a memory buffer. - * - * Alternatively, you can use a custom stream that reads directly from e.g. - * a file or a network socket. - */ -pb_istream_t pb_istream_from_buffer(uint8_t *buf, size_t bufsize); - -/* Function to read from a pb_istream_t. You can use this if you need to - * read some custom header data, or to read data in field callbacks. - */ -bool pb_read(pb_istream_t *stream, uint8_t *buf, size_t count); - - -/************************************************ - * Helper functions for writing field callbacks * - ************************************************/ - -/* Decode the tag for the next field in the stream. Gives the wire type and - * field tag. At end of the message, returns false and sets eof to true. */ -bool pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, uint32_t *tag, bool *eof); - -/* Skip the field payload data, given the wire type. */ -bool pb_skip_field(pb_istream_t *stream, pb_wire_type_t wire_type); - -/* Decode an integer in the varint format. This works for bool, enum, int32, - * int64, uint32 and uint64 field types. */ -bool pb_decode_varint(pb_istream_t *stream, uint64_t *dest); - -/* Decode an integer in the zig-zagged svarint format. This works for sint32 - * and sint64. */ -bool pb_decode_svarint(pb_istream_t *stream, int64_t *dest); - -/* Decode a fixed32, sfixed32 or float value. You need to pass a pointer to - * a 4-byte wide C variable. */ -bool pb_decode_fixed32(pb_istream_t *stream, void *dest); - -/* Decode a fixed64, sfixed64 or double value. You need to pass a pointer to - * a 8-byte wide C variable. */ -bool pb_decode_fixed64(pb_istream_t *stream, void *dest); - -/* Make a limited-length substream for reading a PB_WT_STRING field. */ -bool pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream); -void pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_encode.h b/fri_client/third_party/nanopb/include/nanopb/pb_encode.h deleted file mode 100644 index 8c7b32c9..00000000 --- a/fri_client/third_party/nanopb/include/nanopb/pb_encode.h +++ /dev/null @@ -1,154 +0,0 @@ -/* pb_encode.h: Functions to encode protocol buffers. Depends on pb_encode.c. - * The main function is pb_encode. You also need an output stream, and the - * field descriptions created by nanopb_generator.py. - */ - -#ifndef _PB_ENCODE_H_ -#define _PB_ENCODE_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/* Structure for defining custom output streams. You will need to provide - * a callback function to write the bytes to your storage, which can be - * for example a file or a network socket. - * - * The callback must conform to these rules: - * - * 1) Return false on IO errors. This will cause encoding to abort. - * 2) You can use state to store your own data (e.g. buffer pointer). - * 3) pb_write will update bytes_written after your callback runs. - * 4) Substreams will modify max_size and bytes_written. Don't use them - * to calculate any pointers. - */ -struct _pb_ostream_t -{ -#ifdef PB_BUFFER_ONLY - /* Callback pointer is not used in buffer-only configuration. - * Having an int pointer here allows binary compatibility but - * gives an error if someone tries to assign callback function. - * Also, NULL pointer marks a 'sizing stream' that does not - * write anything. - */ - int *callback; -#else - bool (*callback)(pb_ostream_t *stream, const uint8_t *buf, size_t count); -#endif - void *state; /* Free field for use by callback implementation. */ - size_t max_size; /* Limit number of output bytes written (or use SIZE_MAX). */ - size_t bytes_written; /* Number of bytes written so far. */ - -#ifndef PB_NO_ERRMSG - const char *errmsg; -#endif -}; - -/*************************** - * Main encoding functions * - ***************************/ - -/* Encode a single protocol buffers message from C structure into a stream. - * Returns true on success, false on any failure. - * The actual struct pointed to by src_struct must match the description in fields. - * All required fields in the struct are assumed to have been filled in. - * - * Example usage: - * MyMessage msg = {}; - * uint8_t buffer[64]; - * pb_ostream_t stream; - * - * msg.field1 = 42; - * stream = pb_ostream_from_buffer(buffer, sizeof(buffer)); - * pb_encode(&stream, MyMessage_fields, &msg); - */ -bool pb_encode(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct); - -/* Same as pb_encode, but prepends the length of the message as a varint. - * Corresponds to writeDelimitedTo() in Google's protobuf API. - */ -bool pb_encode_delimited(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct); - -/* Encode the message to get the size of the encoded data, but do not store - * the data. */ -bool pb_get_encoded_size(size_t *size, const pb_field_t fields[], const void *src_struct); - -/************************************** - * Functions for manipulating streams * - **************************************/ - -/* Create an output stream for writing into a memory buffer. - * The number of bytes written can be found in stream.bytes_written after - * encoding the message. - * - * Alternatively, you can use a custom stream that writes directly to e.g. - * a file or a network socket. - */ -pb_ostream_t pb_ostream_from_buffer(uint8_t *buf, size_t bufsize); - -/* Pseudo-stream for measuring the size of a message without actually storing - * the encoded data. - * - * Example usage: - * MyMessage msg = {}; - * pb_ostream_t stream = PB_OSTREAM_SIZING; - * pb_encode(&stream, MyMessage_fields, &msg); - * printf("Message size is %d\n", stream.bytes_written); - */ -#ifndef PB_NO_ERRMSG -#define PB_OSTREAM_SIZING {0,0,0,0,0} -#else -#define PB_OSTREAM_SIZING {0,0,0,0} -#endif - -/* Function to write into a pb_ostream_t stream. You can use this if you need - * to append or prepend some custom headers to the message. - */ -bool pb_write(pb_ostream_t *stream, const uint8_t *buf, size_t count); - - -/************************************************ - * Helper functions for writing field callbacks * - ************************************************/ - -/* Encode field header based on type and field number defined in the field - * structure. Call this from the callback before writing out field contents. */ -bool pb_encode_tag_for_field(pb_ostream_t *stream, const pb_field_t *field); - -/* Encode field header by manually specifing wire type. You need to use this - * if you want to write out packed arrays from a callback field. */ -bool pb_encode_tag(pb_ostream_t *stream, pb_wire_type_t wiretype, uint32_t field_number); - -/* Encode an integer in the varint format. - * This works for bool, enum, int32, int64, uint32 and uint64 field types. */ -bool pb_encode_varint(pb_ostream_t *stream, uint64_t value); - -/* Encode an integer in the zig-zagged svarint format. - * This works for sint32 and sint64. */ -bool pb_encode_svarint(pb_ostream_t *stream, int64_t value); - -/* Encode a string or bytes type field. For strings, pass strlen(s) as size. */ -bool pb_encode_string(pb_ostream_t *stream, const uint8_t *buffer, size_t size); - -/* Encode a fixed32, sfixed32 or float value. - * You need to pass a pointer to a 4-byte wide C variable. */ -bool pb_encode_fixed32(pb_ostream_t *stream, const void *value); - -/* Encode a fixed64, sfixed64 or double value. - * You need to pass a pointer to a 8-byte wide C variable. */ -bool pb_encode_fixed64(pb_ostream_t *stream, const void *value); - -/* Encode a submessage field. - * You need to pass the pb_field_t array and pointer to struct, just like - * with pb_encode(). This internally encodes the submessage twice, first to - * calculate message size and then to actually write it out. - */ -bool pb_encode_submessage(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h b/fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h deleted file mode 100644 index d437000c..00000000 --- a/fri_client/third_party/nanopb/include/nanopb/pb_syshdr.h +++ /dev/null @@ -1,127 +0,0 @@ -/* This is an example of a header file for platforms/compilers that do - * not come with stdint.h/stddef.h/stdbool.h/string.h. To use it, define - * PB_SYSTEM_HEADER as "pb_syshdr.h", including the quotes, and add the - * extra folder to your include path. - * - * It is very likely that you will need to customize this file to suit - * your platform. For any compiler that supports C99, this file should - * not be necessary. - * - * KUKA: Added VXWORKS support - */ - -#ifndef _PB_SYSHDR_H_ -#define _PB_SYSHDR_H_ - -/* KUKA VxWorks 6.8 support */ -#ifdef VXWORKS - #define HAVE_STRING_H - #define HAVE_STDLIB_H -#ifdef _WRS_KERNEL - #include // int32_t, int64_t, ... - #define HAVE_STDINT_H_ALTERNATIVE - #define HAVE_STDDEF_H_ALTERNATIVE -#else - #define HAVE_STDINT_H - #define HAVE_STDDEF_H -#endif // _WRS_KERNEL -#endif // VXWORKS - -/* KUKA: size_t is defined in stddef.h, stdlib.h or string.h */ -#if !defined(HAVE_STDDEF_H) && !defined(HAVE_STDLIB_H) && !defined(HAVE_STRING_H) -typedef uint32_t size_t; -#endif - - - -/* stdint.h subset */ -#ifdef HAVE_STDINT_H -#include -#else -#ifndef HAVE_STDINT_H_ALTERNATIVE -/* You will need to modify these to match the word size of your platform. */ -typedef signed char int8_t; -typedef unsigned char uint8_t; -typedef signed short int16_t; -typedef unsigned short uint16_t; -typedef signed int int32_t; -typedef unsigned int uint32_t; -typedef signed long long int64_t; -typedef unsigned long long uint64_t; -#endif // HAVE_STDINT_H_ALTERNATIVE -#endif // HAVE_STDINT_H - -/* stddef.h subset */ -#ifdef HAVE_STDDEF_H -#include -#else -#ifndef HAVE_STDDEF_H_ALTERNATIVE -#define offsetof(st, m) ((size_t)(&((st *)0)->m)) -#ifndef NULL -#define NULL 0 -#endif // NULL -#endif // HAVE_STDDEF_H_ALTERNATIVE -#endif // HAVE_STDDEF_H - -/* stdbool.h subset */ -#ifdef HAVE_STDBOOL_H -#include -#else - -#ifndef __cplusplus -typedef int bool; -#define false 0 -#define true 1 -#endif - -#endif // HAVE_STDBOOL_H - -/* stdlib.h subset */ -#ifdef PB_ENABLE_MALLOC -#ifdef HAVE_STDLIB_H -#include -#else -void *realloc(void *ptr, size_t size); -void free(void *ptr); -#endif // HAVE_STDLIB_H -#endif // PB_ENABLE_MALLOC - -/* string.h subset */ -#ifdef HAVE_STRING_H -#include -#else - -/* Implementations are from the Public Domain C Library (PDCLib). */ -static size_t strlen( const char * s ) -{ - size_t rc = 0; - while ( s[rc] ) - { - ++rc; - } - return rc; -} - -static void * memcpy( void *s1, const void *s2, size_t n ) -{ - char * dest = (char *) s1; - const char * src = (const char *) s2; - while ( n-- ) - { - *dest++ = *src++; - } - return s1; -} - -static void * memset( void * s, int c, size_t n ) -{ - unsigned char * p = (unsigned char *) s; - while ( n-- ) - { - *p++ = (unsigned char) c; - } - return s; -} -#endif // HAVE_STRING_H - -#endif // _PB_SYSHDR_H_ diff --git a/fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h b/fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h deleted file mode 100644 index 73bbb64f..00000000 --- a/fri_client/third_party/nanopb/include/nanopb/pb_syshdr_win.h +++ /dev/null @@ -1,119 +0,0 @@ -/* This is a headerfile customized for Microsoft Visual Studio 2010 - * - based on example of a header file for platforms/compilers that do - * not come with stdint.h/stddef.h/stdbool.h/string.h. To use it, define - * PB_SYSTEM_HEADER as "pb_syshdr_win.h", including the quotes, and add the - * extra folder to your include path. - * - * Authorship: This file was altered/created by KUKA Roboter GmbH, Augsburg, Germany in 2014 - * - */ - -#ifndef _PB_SYSHDR_WIN_H_ -#define _PB_SYSHDR_WIN_H_ - -/* stdint.h subset */ -#ifdef HAVE_STDINT_H -#include -#else -/* You will need to modify these to match the word size of your platform. */ -typedef signed char int8_t; -typedef unsigned char uint8_t; -typedef signed short int16_t; -typedef unsigned short uint16_t; -typedef signed int int32_t; -typedef unsigned int uint32_t; -typedef signed long long int64_t; -typedef unsigned long long uint64_t; - -// from stdint.h -#define INT8_MAX 0x7f -#define INT16_MAX 0x7fff -#define INT32_MAX 0x7fffffff -#define UINT8_MAX 0xffU -#define UINT16_MAX 0xffffU -#define UINT32_MAX 0xffffffffU -#endif - -/* stddef.h subset */ -#ifdef HAVE_STDDEF_H -#include -#else - -//typedef uint32_t size_t; // wird dieser typedef wirklich benötigt?!? -#ifndef offsetof -#define offsetof(st, m) ((size_t)(&((st *)0)->m)) -#endif - -#ifndef NULL -#define NULL 0 -#endif - -#endif - -/* stdbool.h subset */ -#ifdef HAVE_STDBOOL_H -#include -#else - -#ifndef __cplusplus -typedef int bool; -#define false 0 -#define true 1 -#endif - -#endif - -/* stdlib.h subset */ -#ifdef PB_ENABLE_MALLOC -#ifdef HAVE_STDLIB_H -#include -#else -void *realloc(void *ptr, size_t size); -void free(void *ptr); -#endif -#endif - -/* string.h subset */ -#ifdef HAVE_STRING_H -#include -#else - -#ifndef WIN32 -/* Implementations are from the Public Domain C Library (PDCLib). */ -static size_t strlen( const char * s ) -{ - size_t rc = 0; - while ( s[rc] ) - { - ++rc; - } - return rc; -} - -static void * memcpy( void *s1, const void *s2, size_t n ) -{ - char * dest = (char *) s1; - const char * src = (const char *) s2; - while ( n-- ) - { - *dest++ = *src++; - } - return s1; -} - -static void * memset( void * s, int c, size_t n ) -{ - unsigned char * p = (unsigned char *) s; - while ( n-- ) - { - *p++ = (unsigned char) c; - } - return s; -} -#else -#include -#endif - -#endif - -#endif diff --git a/fri_client/third_party/nanopb/src/pb_decode.c b/fri_client/third_party/nanopb/src/pb_decode.c deleted file mode 100644 index 8e34b179..00000000 --- a/fri_client/third_party/nanopb/src/pb_decode.c +++ /dev/null @@ -1,1198 +0,0 @@ -/* pb_decode.c -- decode a protobuf using minimal resources - * - * 2011 Petteri Aimonen - */ - -/* Use the GCC warn_unused_result attribute to check that all return values - * are propagated correctly. On other compilers and gcc before 3.4.0 just - * ignore the annotation. - */ -#if !defined(__GNUC__) || ( __GNUC__ < 3) || (__GNUC__ == 3 && __GNUC_MINOR__ < 4) - #define checkreturn -#else - #define checkreturn __attribute__((warn_unused_result)) -#endif - -#include -#include - -/************************************** - * Declarations internal to this file * - **************************************/ - -/* Iterator for pb_field_t list */ -typedef struct { - const pb_field_t *start; /* Start of the pb_field_t array */ - const pb_field_t *pos; /* Current position of the iterator */ - unsigned field_index; /* Zero-based index of the field. */ - unsigned required_field_index; /* Zero-based index that counts only the required fields */ - void *dest_struct; /* Pointer to the destination structure to decode to */ - void *pData; /* Pointer where to store current field value */ - void *pSize; /* Pointer where to store the size of current array field */ -} pb_field_iterator_t; - -typedef bool (*pb_decoder_t)(pb_istream_t *stream, const pb_field_t *field, void *dest) checkreturn; - -static bool checkreturn buf_read(pb_istream_t *stream, uint8_t *buf, size_t count); -static bool checkreturn pb_decode_varint32(pb_istream_t *stream, uint32_t *dest); -static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire_type, uint8_t *buf, size_t *size); -static void pb_field_init(pb_field_iterator_t *iter, const pb_field_t *fields, void *dest_struct); -static bool pb_field_next(pb_field_iterator_t *iter); -static bool checkreturn pb_field_find(pb_field_iterator_t *iter, uint32_t tag); -static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter); -static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter); -static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter); -static bool checkreturn default_extension_decoder(pb_istream_t *stream, pb_extension_t *extension, uint32_t tag, pb_wire_type_t wire_type); -static bool checkreturn decode_extension(pb_istream_t *stream, uint32_t tag, pb_wire_type_t wire_type, pb_field_iterator_t *iter); -static bool checkreturn find_extension_field(pb_field_iterator_t *iter); -static void pb_message_set_to_defaults(const pb_field_t fields[], void *dest_struct); -static bool checkreturn pb_dec_varint(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_uvarint(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_svarint(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_fixed32(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_fixed64(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_t *field, void *dest); -static bool checkreturn pb_skip_varint(pb_istream_t *stream); -static bool checkreturn pb_skip_string(pb_istream_t *stream); - -/* --- Function pointers to field decoders --- - * Order in the array must match pb_action_t LTYPE numbering. - */ -static const pb_decoder_t PB_DECODERS[PB_LTYPES_COUNT] = { - &pb_dec_varint, - &pb_dec_uvarint, - &pb_dec_svarint, - &pb_dec_fixed32, - &pb_dec_fixed64, - - &pb_dec_bytes, - &pb_dec_string, - &pb_dec_submessage, - NULL /* extensions */ -}; - -/******************************* - * pb_istream_t implementation * - *******************************/ - -static bool checkreturn buf_read(pb_istream_t *stream, uint8_t *buf, size_t count) -{ - uint8_t *source = (uint8_t*)stream->state; - stream->state = source + count; - - if (buf != NULL) - { - while (count--) - *buf++ = *source++; - } - - return true; -} - -bool checkreturn pb_read(pb_istream_t *stream, uint8_t *buf, size_t count) -{ -#ifndef PB_BUFFER_ONLY - if (buf == NULL && stream->callback != buf_read) - { - /* Skip input bytes */ - uint8_t tmp[16]; - while (count > 16) - { - if (!pb_read(stream, tmp, 16)) - return false; - - count -= 16; - } - - return pb_read(stream, tmp, count); - } -#endif - - if (stream->bytes_left < count) - PB_RETURN_ERROR(stream, "end-of-stream"); - -#ifndef PB_BUFFER_ONLY - if (!stream->callback(stream, buf, count)) - PB_RETURN_ERROR(stream, "io error"); -#else - if (!buf_read(stream, buf, count)) - return false; -#endif - - stream->bytes_left -= count; - return true; -} - -/* Read a single byte from input stream. buf may not be NULL. - * This is an optimization for the varint decoding. */ -static bool checkreturn pb_readbyte(pb_istream_t *stream, uint8_t *buf) -{ - if (stream->bytes_left == 0) - PB_RETURN_ERROR(stream, "end-of-stream"); - -#ifndef PB_BUFFER_ONLY - if (!stream->callback(stream, buf, 1)) - PB_RETURN_ERROR(stream, "io error"); -#else - *buf = *(uint8_t*)stream->state; - stream->state = (uint8_t*)stream->state + 1; -#endif - - stream->bytes_left--; - - return true; -} - -pb_istream_t pb_istream_from_buffer(uint8_t *buf, size_t bufsize) -{ - pb_istream_t stream; -#ifdef PB_BUFFER_ONLY - stream.callback = NULL; -#else - stream.callback = &buf_read; -#endif - stream.state = buf; - stream.bytes_left = bufsize; -#ifndef PB_NO_ERRMSG - stream.errmsg = NULL; -#endif - return stream; -} - -/******************** - * Helper functions * - ********************/ - -static bool checkreturn pb_decode_varint32(pb_istream_t *stream, uint32_t *dest) -{ - uint8_t byte; - uint32_t result; - - if (!pb_readbyte(stream, &byte)) - return false; - - if ((byte & 0x80) == 0) - { - /* Quick case, 1 byte value */ - result = byte; - } - else - { - /* Multibyte case */ - uint8_t bitpos = 7; - result = byte & 0x7F; - - do - { - if (bitpos >= 32) - PB_RETURN_ERROR(stream, "varint overflow"); - - if (!pb_readbyte(stream, &byte)) - return false; - - result |= (uint32_t)(byte & 0x7F) << bitpos; - bitpos = (uint8_t)(bitpos + 7); - } while (byte & 0x80); - } - - *dest = result; - return true; -} - -bool checkreturn pb_decode_varint(pb_istream_t *stream, uint64_t *dest) -{ - uint8_t byte; - uint8_t bitpos = 0; - uint64_t result = 0; - - do - { - if (bitpos >= 64) - PB_RETURN_ERROR(stream, "varint overflow"); - - if (!pb_readbyte(stream, &byte)) - return false; - - result |= (uint64_t)(byte & 0x7F) << bitpos; - bitpos = (uint8_t)(bitpos + 7); - } while (byte & 0x80); - - *dest = result; - return true; -} - -bool checkreturn pb_skip_varint(pb_istream_t *stream) -{ - uint8_t byte; - do - { - if (!pb_read(stream, &byte, 1)) - return false; - } while (byte & 0x80); - return true; -} - -bool checkreturn pb_skip_string(pb_istream_t *stream) -{ - uint32_t length; - if (!pb_decode_varint32(stream, &length)) - return false; - - return pb_read(stream, NULL, length); -} - -bool checkreturn pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, uint32_t *tag, bool *eof) -{ - uint32_t temp; - *eof = false; - *wire_type = (pb_wire_type_t) 0; - *tag = 0; - - if (!pb_decode_varint32(stream, &temp)) - { - if (stream->bytes_left == 0) - *eof = true; - - return false; - } - - if (temp == 0) - { - *eof = true; /* Special feature: allow 0-terminated messages. */ - return false; - } - - *tag = temp >> 3; - *wire_type = (pb_wire_type_t)(temp & 7); - return true; -} - -bool checkreturn pb_skip_field(pb_istream_t *stream, pb_wire_type_t wire_type) -{ - switch (wire_type) - { - case PB_WT_VARINT: return pb_skip_varint(stream); - case PB_WT_64BIT: return pb_read(stream, NULL, 8); - case PB_WT_STRING: return pb_skip_string(stream); - case PB_WT_32BIT: return pb_read(stream, NULL, 4); - default: PB_RETURN_ERROR(stream, "invalid wire_type"); - } -} - -/* Read a raw value to buffer, for the purpose of passing it to callback as - * a substream. Size is maximum size on call, and actual size on return. - */ -static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire_type, uint8_t *buf, size_t *size) -{ - size_t max_size = *size; - switch (wire_type) - { - case PB_WT_VARINT: - *size = 0; - do - { - (*size)++; - if (*size > max_size) return false; - if (!pb_read(stream, buf, 1)) return false; - } while (*buf++ & 0x80); - return true; - - case PB_WT_64BIT: - *size = 8; - return pb_read(stream, buf, 8); - - case PB_WT_32BIT: - *size = 4; - return pb_read(stream, buf, 4); - - default: PB_RETURN_ERROR(stream, "invalid wire_type"); - } -} - -/* Decode string length from stream and return a substream with limited length. - * Remember to close the substream using pb_close_string_substream(). - */ -bool checkreturn pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream) -{ - uint32_t size; - if (!pb_decode_varint32(stream, &size)) - return false; - - *substream = *stream; - if (substream->bytes_left < size) - PB_RETURN_ERROR(stream, "parent stream too short"); - - substream->bytes_left = size; - stream->bytes_left -= size; - return true; -} - -void pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream) -{ - stream->state = substream->state; - -#ifndef PB_NO_ERRMSG - stream->errmsg = substream->errmsg; -#endif -} - -static void pb_field_init(pb_field_iterator_t *iter, const pb_field_t *fields, void *dest_struct) -{ - iter->start = iter->pos = fields; - iter->field_index = 0; - iter->required_field_index = 0; - iter->pData = (char*)dest_struct + iter->pos->data_offset; - iter->pSize = (char*)iter->pData + iter->pos->size_offset; - iter->dest_struct = dest_struct; -} - -static bool pb_field_next(pb_field_iterator_t *iter) -{ - bool notwrapped = true; - size_t prev_size = iter->pos->data_size; - - if (PB_ATYPE(iter->pos->type) == PB_ATYPE_STATIC && - PB_HTYPE(iter->pos->type) == PB_HTYPE_REPEATED) - { - prev_size *= iter->pos->array_size; - } - else if (PB_ATYPE(iter->pos->type) == PB_ATYPE_POINTER) - { - prev_size = sizeof(void*); - } - - if (iter->pos->tag == 0) - return false; /* Only happens with empty message types */ - - if (PB_HTYPE(iter->pos->type) == PB_HTYPE_REQUIRED) - iter->required_field_index++; - - iter->pos++; - iter->field_index++; - if (iter->pos->tag == 0) - { - iter->pos = iter->start; - iter->field_index = 0; - iter->required_field_index = 0; - iter->pData = iter->dest_struct; - prev_size = 0; - notwrapped = false; - } - - iter->pData = (char*)iter->pData + prev_size + iter->pos->data_offset; - iter->pSize = (char*)iter->pData + iter->pos->size_offset; - return notwrapped; -} - -static bool checkreturn pb_field_find(pb_field_iterator_t *iter, uint32_t tag) -{ - unsigned start = iter->field_index; - - do { - if (iter->pos->tag == tag && - PB_LTYPE(iter->pos->type) != PB_LTYPE_EXTENSION) - { - return true; - } - (void)pb_field_next(iter); - } while (iter->field_index != start); - - return false; -} - -/************************* - * Decode a single field * - *************************/ - -static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) -{ - pb_type_t type; - pb_decoder_t func; - - type = iter->pos->type; - func = PB_DECODERS[PB_LTYPE(type)]; - - switch (PB_HTYPE(type)) - { - case PB_HTYPE_REQUIRED: - return func(stream, iter->pos, iter->pData); - - case PB_HTYPE_OPTIONAL: - *(bool*)iter->pSize = true; - return func(stream, iter->pos, iter->pData); - - case PB_HTYPE_REPEATED: - if (wire_type == PB_WT_STRING - && PB_LTYPE(type) <= PB_LTYPE_LAST_PACKABLE) - { - /* Packed array */ - bool status = true; - size_t *size = (size_t*)iter->pSize; - pb_istream_t substream; - if (!pb_make_string_substream(stream, &substream)) - return false; - - while (substream.bytes_left > 0 && *size < iter->pos->array_size) - { - void *pItem = (uint8_t*)iter->pData + iter->pos->data_size * (*size); - if (!func(&substream, iter->pos, pItem)) - { - status = false; - break; - } - (*size)++; - } - pb_close_string_substream(stream, &substream); - - if (substream.bytes_left != 0) - PB_RETURN_ERROR(stream, "array overflow"); - - return status; - } - else - { - /* Repeated field */ - size_t *size = (size_t*)iter->pSize; - void *pItem = (uint8_t*)iter->pData + iter->pos->data_size * (*size); - if (*size >= iter->pos->array_size) - PB_RETURN_ERROR(stream, "array overflow"); - - (*size)++; - return func(stream, iter->pos, pItem); - } - - default: - PB_RETURN_ERROR(stream, "invalid field type"); - } -} - -#ifdef PB_ENABLE_MALLOC -/* Allocate storage for the field and store the pointer at iter->pData. - * array_size is the number of entries to reserve in an array. - */ -static bool checkreturn allocate_field(pb_istream_t *stream, void *pData, size_t data_size, size_t array_size) -{ - void *ptr = *(void**)pData; - - /* Check for multiplication overflows. */ - size_t size = 0; - if (data_size > 0 && array_size > 0) - { - /* Avoid the costly division if the sizes are small enough. - * Multiplication is safe as long as only half of bits are set - * in either multiplicand. - */ - const size_t check_limit = (size_t)1 << (sizeof(size_t) * 4); - if (data_size >= check_limit || array_size >= check_limit) - { - if (SIZE_MAX / array_size < data_size) - { - PB_RETURN_ERROR(stream, "size too large"); - } - } - - size = array_size * data_size; - } - - /* Allocate new or expand previous allocation */ - /* Note: on failure the old pointer will remain in the structure, - * the message must be freed by caller also on error return. */ - ptr = pb_realloc(ptr, size); - if (ptr == NULL) - PB_RETURN_ERROR(stream, "realloc failed"); - - *(void**)pData = ptr; - return true; -} - -/* Clear a newly allocated item in case it contains a pointer, or is a submessage. */ -static void initialize_pointer_field(void *pItem, pb_field_iterator_t *iter) -{ - if (PB_LTYPE(iter->pos->type) == PB_LTYPE_STRING || - PB_LTYPE(iter->pos->type) == PB_LTYPE_BYTES) - { - *(void**)pItem = NULL; - } - else if (PB_LTYPE(iter->pos->type) == PB_LTYPE_SUBMESSAGE) - { - pb_message_set_to_defaults((const pb_field_t *) iter->pos->ptr, pItem); - } -} -#endif - -static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) -{ -#ifndef PB_ENABLE_MALLOC - UNUSED(wire_type); - UNUSED(iter); - PB_RETURN_ERROR(stream, "no malloc support"); -#else - pb_type_t type; - pb_decoder_t func; - - type = iter->pos->type; - func = PB_DECODERS[PB_LTYPE(type)]; - - switch (PB_HTYPE(type)) - { - case PB_HTYPE_REQUIRED: - case PB_HTYPE_OPTIONAL: - if (PB_LTYPE(type) == PB_LTYPE_STRING || - PB_LTYPE(type) == PB_LTYPE_BYTES) - { - return func(stream, iter->pos, iter->pData); - } - else - { - if (!allocate_field(stream, iter->pData, iter->pos->data_size, 1)) - return false; - - initialize_pointer_field(*(void**)iter->pData, iter); - return func(stream, iter->pos, *(void**)iter->pData); - } - - case PB_HTYPE_REPEATED: - if (wire_type == PB_WT_STRING - && PB_LTYPE(type) <= PB_LTYPE_LAST_PACKABLE) - { - /* Packed array, multiple items come in at once. */ - bool status = true; - size_t *size = (size_t*)iter->pSize; - size_t allocated_size = *size; - void *pItem; - pb_istream_t substream; - - if (!pb_make_string_substream(stream, &substream)) - return false; - - while (substream.bytes_left) - { - if (*size + 1 > allocated_size) - { - /* Allocate more storage. This tries to guess the - * number of remaining entries. Round the division - * upwards. */ - allocated_size += (substream.bytes_left - 1) / iter->pos->data_size + 1; - - if (!allocate_field(&substream, iter->pData, iter->pos->data_size, allocated_size)) - { - status = false; - break; - } - } - - /* Decode the array entry */ - pItem = *(uint8_t**)iter->pData + iter->pos->data_size * (*size); - initialize_pointer_field(pItem, iter); - if (!func(&substream, iter->pos, pItem)) - { - status = false; - break; - } - (*size)++; - } - pb_close_string_substream(stream, &substream); - - return status; - } - else - { - /* Normal repeated field, i.e. only one item at a time. */ - size_t *size = (size_t*)iter->pSize; - void *pItem; - - (*size)++; - if (!allocate_field(stream, iter->pData, iter->pos->data_size, *size)) - return false; - - pItem = *(uint8_t**)iter->pData + iter->pos->data_size * (*size - 1); - initialize_pointer_field(pItem, iter); - return func(stream, iter->pos, pItem); - } - - default: - PB_RETURN_ERROR(stream, "invalid field type"); - } -#endif -} - -static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) -{ - pb_callback_t *pCallback = (pb_callback_t*)iter->pData; - -#ifdef PB_OLD_CALLBACK_STYLE - void *arg = pCallback->arg; -#else - void **arg = &(pCallback->arg); -#endif - - if (pCallback->funcs.decode == NULL) - return pb_skip_field(stream, wire_type); - - if (wire_type == PB_WT_STRING) - { - pb_istream_t substream; - - if (!pb_make_string_substream(stream, &substream)) - return false; - - do - { - if (!pCallback->funcs.decode(&substream, iter->pos, arg)) - PB_RETURN_ERROR(stream, "callback failed"); - } while (substream.bytes_left); - - pb_close_string_substream(stream, &substream); - return true; - } - else - { - /* Copy the single scalar value to stack. - * This is required so that we can limit the stream length, - * which in turn allows to use same callback for packed and - * not-packed fields. */ - pb_istream_t substream; - uint8_t buffer[10]; - size_t size = sizeof(buffer); - - if (!read_raw_value(stream, wire_type, buffer, &size)) - return false; - substream = pb_istream_from_buffer(buffer, size); - - return pCallback->funcs.decode(&substream, iter->pos, arg); - } -} - -static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iterator_t *iter) -{ - switch (PB_ATYPE(iter->pos->type)) - { - case PB_ATYPE_STATIC: - return decode_static_field(stream, wire_type, iter); - - case PB_ATYPE_POINTER: - return decode_pointer_field(stream, wire_type, iter); - - case PB_ATYPE_CALLBACK: - return decode_callback_field(stream, wire_type, iter); - - default: - PB_RETURN_ERROR(stream, "invalid field type"); - } -} - -/* Default handler for extension fields. Expects a pb_field_t structure - * in extension->type->arg. */ -static bool checkreturn default_extension_decoder(pb_istream_t *stream, - pb_extension_t *extension, uint32_t tag, pb_wire_type_t wire_type) -{ - const pb_field_t *field = (const pb_field_t*)extension->type->arg; - pb_field_iterator_t iter; - - if (field->tag != tag) - return true; - - iter.start = field; - iter.pos = field; - iter.field_index = 0; - iter.required_field_index = 0; - iter.dest_struct = extension->dest; - iter.pData = extension->dest; - iter.pSize = &extension->found; - - return decode_field(stream, wire_type, &iter); -} - -/* Try to decode an unknown field as an extension field. Tries each extension - * decoder in turn, until one of them handles the field or loop ends. */ -static bool checkreturn decode_extension(pb_istream_t *stream, - uint32_t tag, pb_wire_type_t wire_type, pb_field_iterator_t *iter) -{ - pb_extension_t *extension = *(pb_extension_t* const *)iter->pData; - size_t pos = stream->bytes_left; - - while (extension != NULL && pos == stream->bytes_left) - { - bool status; - if (extension->type->decode) - status = extension->type->decode(stream, extension, tag, wire_type); - else - status = default_extension_decoder(stream, extension, tag, wire_type); - - if (!status) - return false; - - extension = extension->next; - } - - return true; -} - -/* Step through the iterator until an extension field is found or until all - * entries have been checked. There can be only one extension field per - * message. Returns false if no extension field is found. */ -static bool checkreturn find_extension_field(pb_field_iterator_t *iter) -{ - unsigned start = iter->field_index; - - do { - if (PB_LTYPE(iter->pos->type) == PB_LTYPE_EXTENSION) - return true; - (void)pb_field_next(iter); - } while (iter->field_index != start); - - return false; -} - -/* Initialize message fields to default values, recursively */ -static void pb_message_set_to_defaults(const pb_field_t fields[], void *dest_struct) -{ - pb_field_iterator_t iter; - pb_field_init(&iter, fields, dest_struct); - - do - { - pb_type_t type; - type = iter.pos->type; - - /* Avoid crash on empty message types (zero fields) */ - if (iter.pos->tag == 0) - continue; - - if (PB_ATYPE(type) == PB_ATYPE_STATIC) - { - if (PB_HTYPE(type) == PB_HTYPE_OPTIONAL) - { - /* Set has_field to false. Still initialize the optional field - * itself also. */ - *(bool*)iter.pSize = false; - } - else if (PB_HTYPE(type) == PB_HTYPE_REPEATED) - { - /* Set array count to 0, no need to initialize contents. */ - *(size_t*)iter.pSize = 0; - continue; - } - - if (PB_LTYPE(iter.pos->type) == PB_LTYPE_SUBMESSAGE) - { - /* Initialize submessage to defaults */ - pb_message_set_to_defaults((const pb_field_t *) iter.pos->ptr, iter.pData); - } - else if (iter.pos->ptr != NULL) - { - /* Initialize to default value */ - memcpy(iter.pData, iter.pos->ptr, iter.pos->data_size); - } - else - { - /* Initialize to zeros */ - memset(iter.pData, 0, iter.pos->data_size); - } - } - else if (PB_ATYPE(type) == PB_ATYPE_POINTER) - { - /* Initialize the pointer to NULL. */ - *(void**)iter.pData = NULL; - - /* Initialize array count to 0. */ - if (PB_HTYPE(type) == PB_HTYPE_REPEATED) - { - *(size_t*)iter.pSize = 0; - } - } - else if (PB_ATYPE(type) == PB_ATYPE_CALLBACK) - { - /* Don't overwrite callback */ - } - } while (pb_field_next(&iter)); -} - -/********************* - * Decode all fields * - *********************/ - -bool checkreturn pb_decode_noinit(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct) -{ - uint8_t fields_seen[(PB_MAX_REQUIRED_FIELDS + 7) / 8] = {0, 0, 0, 0, 0, 0, 0, 0}; - uint32_t extension_range_start = 0; - pb_field_iterator_t iter; - - pb_field_init(&iter, fields, dest_struct); - - while (stream->bytes_left) - { - uint32_t tag; - pb_wire_type_t wire_type; - bool eof; - - if (!pb_decode_tag(stream, &wire_type, &tag, &eof)) - { - if (eof) - break; - else - return false; - } - - if (!pb_field_find(&iter, tag)) - { - /* No match found, check if it matches an extension. */ - if (tag >= extension_range_start) - { - if (!find_extension_field(&iter)) - extension_range_start = (uint32_t)-1; - else - extension_range_start = iter.pos->tag; - - if (tag >= extension_range_start) - { - size_t pos = stream->bytes_left; - - if (!decode_extension(stream, tag, wire_type, &iter)) - return false; - - if (pos != stream->bytes_left) - { - /* The field was handled */ - continue; - } - } - } - - /* No match found, skip data */ - if (!pb_skip_field(stream, wire_type)) - return false; - continue; - } - - if (PB_HTYPE(iter.pos->type) == PB_HTYPE_REQUIRED - && iter.required_field_index < PB_MAX_REQUIRED_FIELDS) - { - fields_seen[iter.required_field_index >> 3] |= (uint8_t)(1 << (iter.required_field_index & 7)); - } - - if (!decode_field(stream, wire_type, &iter)) - return false; - } - - /* Check that all required fields were present. */ - { - /* First figure out the number of required fields by - * seeking to the end of the field array. Usually we - * are already close to end after decoding. - */ - unsigned req_field_count; - pb_type_t last_type; - unsigned i; - do { - req_field_count = iter.required_field_index; - last_type = iter.pos->type; - } while (pb_field_next(&iter)); - - /* Fixup if last field was also required. */ - if (PB_HTYPE(last_type) == PB_HTYPE_REQUIRED && iter.pos->tag != 0) - req_field_count++; - - /* Check the whole bytes */ - for (i = 0; i < (req_field_count >> 3); i++) - { - if (fields_seen[i] != 0xFF) - PB_RETURN_ERROR(stream, "missing required field"); - } - - /* Check the remaining bits */ - if (fields_seen[req_field_count >> 3] != (0xFF >> (8 - (req_field_count & 7)))) - PB_RETURN_ERROR(stream, "missing required field"); - } - - return true; -} - -bool checkreturn pb_decode(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct) -{ - bool status; - pb_message_set_to_defaults(fields, dest_struct); - status = pb_decode_noinit(stream, fields, dest_struct); - -#ifdef PB_ENABLE_MALLOC - if (!status) - pb_release(fields, dest_struct); -#endif - - return status; -} - -bool pb_decode_delimited(pb_istream_t *stream, const pb_field_t fields[], void *dest_struct) -{ - pb_istream_t substream; - bool status; - - if (!pb_make_string_substream(stream, &substream)) - return false; - - status = pb_decode(&substream, fields, dest_struct); - pb_close_string_substream(stream, &substream); - return status; -} - -#ifdef PB_ENABLE_MALLOC -void pb_release(const pb_field_t fields[], void *dest_struct) -{ - pb_field_iterator_t iter; - pb_field_init(&iter, fields, dest_struct); - - do - { - pb_type_t type; - type = iter.pos->type; - - /* Avoid crash on empty message types (zero fields) */ - if (iter.pos->tag == 0) - continue; - - if (PB_ATYPE(type) == PB_ATYPE_POINTER) - { - if (PB_HTYPE(type) == PB_HTYPE_REPEATED && - (PB_LTYPE(type) == PB_LTYPE_STRING || - PB_LTYPE(type) == PB_LTYPE_BYTES)) - { - /* Release entries in repeated string or bytes array */ - void **pItem = *(void***)iter.pData; - size_t count = *(size_t*)iter.pSize; - while (count--) - { - pb_free(*pItem); - *pItem++ = NULL; - } - } - else if (PB_LTYPE(type) == PB_LTYPE_SUBMESSAGE) - { - /* Release fields in submessages */ - void *pItem = *(void**)iter.pData; - size_t count = (pItem ? 1 : 0); - - if (PB_HTYPE(type) == PB_HTYPE_REPEATED) - { - count = *(size_t*)iter.pSize; - } - - while (count--) - { - pb_release((const pb_field_t*)iter.pos->ptr, pItem); - pItem = (uint8_t*)pItem + iter.pos->data_size; - } - } - - /* Release main item */ - pb_free(*(void**)iter.pData); - *(void**)iter.pData = NULL; - } - } while (pb_field_next(&iter)); -} -#endif - -/* Field decoders */ - -bool pb_decode_svarint(pb_istream_t *stream, int64_t *dest) -{ - uint64_t value; - if (!pb_decode_varint(stream, &value)) - return false; - - if (value & 1) - *dest = (int64_t)(~(value >> 1)); - else - *dest = (int64_t)(value >> 1); - - return true; -} - -bool pb_decode_fixed32(pb_istream_t *stream, void *dest) -{ - #ifdef __BIG_ENDIAN__ - uint8_t *bytes = (uint8_t*)dest; - uint8_t lebytes[4]; - - if (!pb_read(stream, lebytes, 4)) - return false; - - bytes[0] = lebytes[3]; - bytes[1] = lebytes[2]; - bytes[2] = lebytes[1]; - bytes[3] = lebytes[0]; - return true; - #else - return pb_read(stream, (uint8_t*)dest, 4); - #endif -} - -bool pb_decode_fixed64(pb_istream_t *stream, void *dest) -{ - #ifdef __BIG_ENDIAN__ - uint8_t *bytes = (uint8_t*)dest; - uint8_t lebytes[8]; - - if (!pb_read(stream, lebytes, 8)) - return false; - - bytes[0] = lebytes[7]; - bytes[1] = lebytes[6]; - bytes[2] = lebytes[5]; - bytes[3] = lebytes[4]; - bytes[4] = lebytes[3]; - bytes[5] = lebytes[2]; - bytes[6] = lebytes[1]; - bytes[7] = lebytes[0]; - return true; - #else - return pb_read(stream, (uint8_t*)dest, 8); - #endif -} - -static bool checkreturn pb_dec_varint(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - uint64_t value; - if (!pb_decode_varint(stream, &value)) - return false; - - switch (field->data_size) - { - case 1: *(int8_t*)dest = (int8_t)value; break; - case 2: *(int16_t*)dest = (int16_t)value; break; - case 4: *(int32_t*)dest = (int32_t)value; break; - case 8: *(int64_t*)dest = (int64_t)value; break; - default: PB_RETURN_ERROR(stream, "invalid data_size"); - } - - return true; -} - -static bool checkreturn pb_dec_uvarint(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - uint64_t value; - if (!pb_decode_varint(stream, &value)) - return false; - - switch (field->data_size) - { - case 4: *(uint32_t*)dest = (uint32_t)value; break; - case 8: *(uint64_t*)dest = value; break; - default: PB_RETURN_ERROR(stream, "invalid data_size"); - } - - return true; -} - -static bool checkreturn pb_dec_svarint(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - int64_t value; - if (!pb_decode_svarint(stream, &value)) - return false; - - switch (field->data_size) - { - case 4: *(int32_t*)dest = (int32_t)value; break; - case 8: *(int64_t*)dest = value; break; - default: PB_RETURN_ERROR(stream, "invalid data_size"); - } - - return true; -} - -static bool checkreturn pb_dec_fixed32(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - UNUSED(field); - return pb_decode_fixed32(stream, dest); -} - -static bool checkreturn pb_dec_fixed64(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - UNUSED(field); - return pb_decode_fixed64(stream, dest); -} - -static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - uint32_t size; - pb_bytes_array_t *bdest; - - if (!pb_decode_varint32(stream, &size)) - return false; - - if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) - { -#ifndef PB_ENABLE_MALLOC - PB_RETURN_ERROR(stream, "no malloc support"); -#else - if (!allocate_field(stream, dest, PB_BYTES_ARRAY_T_ALLOCSIZE(size), 1)) - return false; - bdest = *(pb_bytes_array_t**)dest; -#endif - } - else - { - if (PB_BYTES_ARRAY_T_ALLOCSIZE(size) > field->data_size) - PB_RETURN_ERROR(stream, "bytes overflow"); - bdest = (pb_bytes_array_t*)dest; - } - - bdest->size = size; - return pb_read(stream, bdest->bytes, size); -} - -static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - uint32_t size; - size_t alloc_size; - bool status; - if (!pb_decode_varint32(stream, &size)) - return false; - - /* Space for null terminator */ - alloc_size = size + 1; - - if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) - { -#ifndef PB_ENABLE_MALLOC - PB_RETURN_ERROR(stream, "no malloc support"); -#else - if (!allocate_field(stream, dest, alloc_size, 1)) - return false; - dest = *(void**)dest; -#endif - } - else - { - if (alloc_size > field->data_size) - PB_RETURN_ERROR(stream, "string overflow"); - } - - status = pb_read(stream, (uint8_t*)dest, size); - *((uint8_t*)dest + size) = 0; - return status; -} - -static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_t *field, void *dest) -{ - bool status; - pb_istream_t substream; - const pb_field_t* submsg_fields = (const pb_field_t*)field->ptr; - - if (!pb_make_string_substream(stream, &substream)) - return false; - - if (field->ptr == NULL) - PB_RETURN_ERROR(stream, "invalid field descriptor"); - - /* New array entries need to be initialized, while required and optional - * submessages have already been initialized in the top-level pb_decode. */ - if (PB_HTYPE(field->type) == PB_HTYPE_REPEATED) - status = pb_decode(&substream, submsg_fields, dest); - else - status = pb_decode_noinit(&substream, submsg_fields, dest); - - pb_close_string_substream(stream, &substream); - return status; -} diff --git a/fri_client/third_party/nanopb/src/pb_encode.c b/fri_client/third_party/nanopb/src/pb_encode.c deleted file mode 100644 index 7fcc5745..00000000 --- a/fri_client/third_party/nanopb/src/pb_encode.c +++ /dev/null @@ -1,671 +0,0 @@ -/* pb_encode.c -- encode a protobuf using minimal resources - * - * 2011 Petteri Aimonen - */ - -#include -#include - -/* Use the GCC warn_unused_result attribute to check that all return values - * are propagated correctly. On other compilers and gcc before 3.4.0 just - * ignore the annotation. - */ -#if !defined(__GNUC__) || ( __GNUC__ < 3) || (__GNUC__ == 3 && __GNUC_MINOR__ < 4) - #define checkreturn -#else - #define checkreturn __attribute__((warn_unused_result)) -#endif - -/************************************** - * Declarations internal to this file * - **************************************/ -typedef bool (*pb_encoder_t)(pb_ostream_t *stream, const pb_field_t *field, const void *src) checkreturn; - -static bool checkreturn buf_write(pb_ostream_t *stream, const uint8_t *buf, size_t count); -static bool checkreturn encode_array(pb_ostream_t *stream, const pb_field_t *field, const void *pData, size_t count, pb_encoder_t func); -static bool checkreturn encode_field(pb_ostream_t *stream, const pb_field_t *field, const void *pData); -static bool checkreturn default_extension_encoder(pb_ostream_t *stream, const pb_extension_t *extension); -static bool checkreturn encode_extension_field(pb_ostream_t *stream, const pb_field_t *field, const void *pData); -static bool checkreturn pb_enc_varint(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_uvarint(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_svarint(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_fixed32(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_fixed64(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_t *field, const void *src); -static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_t *field, const void *src); - -/* --- Function pointers to field encoders --- - * Order in the array must match pb_action_t LTYPE numbering. - */ -static const pb_encoder_t PB_ENCODERS[PB_LTYPES_COUNT] = { - &pb_enc_varint, - &pb_enc_uvarint, - &pb_enc_svarint, - &pb_enc_fixed32, - &pb_enc_fixed64, - - &pb_enc_bytes, - &pb_enc_string, - &pb_enc_submessage, - NULL /* extensions */ -}; - -/******************************* - * pb_ostream_t implementation * - *******************************/ - -static bool checkreturn buf_write(pb_ostream_t *stream, const uint8_t *buf, size_t count) -{ - uint8_t *dest = (uint8_t*)stream->state; - stream->state = dest + count; - - while (count--) - *dest++ = *buf++; - - return true; -} - -pb_ostream_t pb_ostream_from_buffer(uint8_t *buf, size_t bufsize) -{ - pb_ostream_t stream; -#ifdef PB_BUFFER_ONLY - stream.callback = (void*)1; /* Just a marker value */ -#else - stream.callback = &buf_write; -#endif - stream.state = buf; - stream.max_size = bufsize; - stream.bytes_written = 0; -#ifndef PB_NO_ERRMSG - stream.errmsg = NULL; -#endif - return stream; -} - -bool checkreturn pb_write(pb_ostream_t *stream, const uint8_t *buf, size_t count) -{ - if (stream->callback != NULL) - { - if (stream->bytes_written + count > stream->max_size) - PB_RETURN_ERROR(stream, "stream full"); - -#ifdef PB_BUFFER_ONLY - if (!buf_write(stream, buf, count)) - PB_RETURN_ERROR(stream, "io error"); -#else - if (!stream->callback(stream, buf, count)) - PB_RETURN_ERROR(stream, "io error"); -#endif - } - - stream->bytes_written += count; - return true; -} - -/************************* - * Encode a single field * - *************************/ - -/* Encode a static array. Handles the size calculations and possible packing. */ -static bool checkreturn encode_array(pb_ostream_t *stream, const pb_field_t *field, - const void *pData, size_t count, pb_encoder_t func) -{ - size_t i; - const void *p; - size_t size; - - if (count == 0) - return true; - - if (PB_ATYPE(field->type) != PB_ATYPE_POINTER && count > field->array_size) - PB_RETURN_ERROR(stream, "array max size exceeded"); - - /* We always pack arrays if the datatype allows it. */ - if (PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) - { - if (!pb_encode_tag(stream, PB_WT_STRING, field->tag)) - return false; - - /* Determine the total size of packed array. */ - if (PB_LTYPE(field->type) == PB_LTYPE_FIXED32) - { - size = 4 * count; - } - else if (PB_LTYPE(field->type) == PB_LTYPE_FIXED64) - { - size = 8 * count; - } - else - { - pb_ostream_t sizestream = PB_OSTREAM_SIZING; - p = pData; - for (i = 0; i < count; i++) - { - if (!func(&sizestream, field, p)) - return false; - p = (const char*)p + field->data_size; - } - size = sizestream.bytes_written; - } - - if (!pb_encode_varint(stream, (uint64_t)size)) - return false; - - if (stream->callback == NULL) - return pb_write(stream, NULL, size); /* Just sizing.. */ - - /* Write the data */ - p = pData; - for (i = 0; i < count; i++) - { - if (!func(stream, field, p)) - return false; - p = (const char*)p + field->data_size; - } - } - else - { - p = pData; - for (i = 0; i < count; i++) - { - if (!pb_encode_tag_for_field(stream, field)) - return false; - - /* Normally the data is stored directly in the array entries, but - * for pointer-type string and bytes fields, the array entries are - * actually pointers themselves also. So we have to dereference once - * more to get to the actual data. */ - if (PB_ATYPE(field->type) == PB_ATYPE_POINTER && - (PB_LTYPE(field->type) == PB_LTYPE_STRING || - PB_LTYPE(field->type) == PB_LTYPE_BYTES)) - { - if (!func(stream, field, *(const void* const*)p)) - return false; - } - else - { - if (!func(stream, field, p)) - return false; - } - p = (const char*)p + field->data_size; - } - } - - return true; -} - -/* Encode a field with static or pointer allocation, i.e. one whose data - * is available to the encoder directly. */ -static bool checkreturn encode_basic_field(pb_ostream_t *stream, - const pb_field_t *field, const void *pData) -{ - pb_encoder_t func; - const void *pSize; - bool implicit_has = true; - - func = PB_ENCODERS[PB_LTYPE(field->type)]; - - if (field->size_offset) - pSize = (const char*)pData + field->size_offset; - else - pSize = &implicit_has; - - if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) - { - /* pData is a pointer to the field, which contains pointer to - * the data. If the 2nd pointer is NULL, it is interpreted as if - * the has_field was false. - */ - - pData = *(const void* const*)pData; - implicit_has = (pData != NULL); - } - - switch (PB_HTYPE(field->type)) - { - case PB_HTYPE_REQUIRED: - if (!pData) - PB_RETURN_ERROR(stream, "missing required field"); - if (!pb_encode_tag_for_field(stream, field)) - return false; - if (!func(stream, field, pData)) - return false; - break; - - case PB_HTYPE_OPTIONAL: - /* - * KUKA adjustment for VxWorks - */ - - if (*(const char*)pSize) - { - if (!pb_encode_tag_for_field(stream, field)) - return false; - - if (!func(stream, field, pData)) - return false; - } - break; - - case PB_HTYPE_REPEATED: - if (!encode_array(stream, field, pData, *(const size_t*)pSize, func)) - return false; - break; - - default: - PB_RETURN_ERROR(stream, "invalid field type"); - } - - return true; -} - -/* Encode a field with callback semantics. This means that a user function is - * called to provide and encode the actual data. */ -static bool checkreturn encode_callback_field(pb_ostream_t *stream, - const pb_field_t *field, const void *pData) -{ - const pb_callback_t *callback = (const pb_callback_t*)pData; - -#ifdef PB_OLD_CALLBACK_STYLE - const void *arg = callback->arg; -#else - void * const *arg = &(callback->arg); -#endif - - if (callback->funcs.encode != NULL) - { - if (!callback->funcs.encode(stream, field, arg)) - PB_RETURN_ERROR(stream, "callback error"); - } - return true; -} - -/* Encode a single field of any callback or static type. */ -static bool checkreturn encode_field(pb_ostream_t *stream, - const pb_field_t *field, const void *pData) -{ - switch (PB_ATYPE(field->type)) - { - case PB_ATYPE_STATIC: - case PB_ATYPE_POINTER: - return encode_basic_field(stream, field, pData); - - case PB_ATYPE_CALLBACK: - return encode_callback_field(stream, field, pData); - - default: - PB_RETURN_ERROR(stream, "invalid field type"); - } -} - -/* Default handler for extension fields. Expects to have a pb_field_t - * pointer in the extension->type->arg field. */ -static bool checkreturn default_extension_encoder(pb_ostream_t *stream, - const pb_extension_t *extension) -{ - const pb_field_t *field = (const pb_field_t*)extension->type->arg; - return encode_field(stream, field, extension->dest); -} - -/* Walk through all the registered extensions and give them a chance - * to encode themselves. */ -static bool checkreturn encode_extension_field(pb_ostream_t *stream, - const pb_field_t *field, const void *pData) -{ - const pb_extension_t *extension = *(const pb_extension_t* const *)pData; - UNUSED(field); - - while (extension) - { - bool status; - if (extension->type->encode) - status = extension->type->encode(stream, extension); - else - status = default_extension_encoder(stream, extension); - - if (!status) - return false; - - extension = extension->next; - } - - return true; -} - -/********************* - * Encode all fields * - *********************/ - -bool checkreturn pb_encode(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct) -{ - const pb_field_t *field = fields; - const void *pData = src_struct; - size_t prev_size = 0; - - while (field->tag != 0) - { - pData = (const char*)pData + prev_size + field->data_offset; - if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) - prev_size = sizeof(const void*); - else - prev_size = field->data_size; - - /* Special case for static arrays */ - if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && - PB_HTYPE(field->type) == PB_HTYPE_REPEATED) - { - prev_size *= field->array_size; - } - - if (PB_LTYPE(field->type) == PB_LTYPE_EXTENSION) - { - /* Special case for the extension field placeholder */ - if (!encode_extension_field(stream, field, pData)) - return false; - } - else - { - /* Regular field */ - if (!encode_field(stream, field, pData)) - return false; - } - - field++; - } - - return true; -} - -bool pb_encode_delimited(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct) -{ - return pb_encode_submessage(stream, fields, src_struct); -} - -bool pb_get_encoded_size(size_t *size, const pb_field_t fields[], const void *src_struct) -{ - pb_ostream_t stream = PB_OSTREAM_SIZING; - - if (!pb_encode(&stream, fields, src_struct)) - return false; - - *size = stream.bytes_written; - return true; -} - -/******************** - * Helper functions * - ********************/ -bool checkreturn pb_encode_varint(pb_ostream_t *stream, uint64_t value) -{ - uint8_t buffer[10]; - size_t i = 0; - - if (value == 0) - return pb_write(stream, (uint8_t*)&value, 1); - - while (value) - { - buffer[i] = (uint8_t)((value & 0x7F) | 0x80); - value >>= 7; - i++; - } - buffer[i-1] &= 0x7F; /* Unset top bit on last byte */ - - return pb_write(stream, buffer, i); -} - -bool checkreturn pb_encode_svarint(pb_ostream_t *stream, int64_t value) -{ - uint64_t zigzagged; - if (value < 0) - zigzagged = ~((uint64_t)value << 1); - else - zigzagged = (uint64_t)value << 1; - - return pb_encode_varint(stream, zigzagged); -} - -bool checkreturn pb_encode_fixed32(pb_ostream_t *stream, const void *value) -{ - #ifdef __BIG_ENDIAN__ - const uint8_t *bytes = value; - uint8_t lebytes[4]; - lebytes[0] = bytes[3]; - lebytes[1] = bytes[2]; - lebytes[2] = bytes[1]; - lebytes[3] = bytes[0]; - return pb_write(stream, lebytes, 4); - #else - return pb_write(stream, (const uint8_t*)value, 4); - #endif -} - -bool checkreturn pb_encode_fixed64(pb_ostream_t *stream, const void *value) -{ - #ifdef __BIG_ENDIAN__ - const uint8_t *bytes = value; - uint8_t lebytes[8]; - lebytes[0] = bytes[7]; - lebytes[1] = bytes[6]; - lebytes[2] = bytes[5]; - lebytes[3] = bytes[4]; - lebytes[4] = bytes[3]; - lebytes[5] = bytes[2]; - lebytes[6] = bytes[1]; - lebytes[7] = bytes[0]; - return pb_write(stream, lebytes, 8); - #else - return pb_write(stream, (const uint8_t*)value, 8); - #endif -} - -bool checkreturn pb_encode_tag(pb_ostream_t *stream, pb_wire_type_t wiretype, uint32_t field_number) -{ - uint64_t tag = ((uint64_t)field_number << 3) | wiretype; - return pb_encode_varint(stream, tag); -} - -bool checkreturn pb_encode_tag_for_field(pb_ostream_t *stream, const pb_field_t *field) -{ - pb_wire_type_t wiretype; - switch (PB_LTYPE(field->type)) - { - case PB_LTYPE_VARINT: - case PB_LTYPE_UVARINT: - case PB_LTYPE_SVARINT: - wiretype = PB_WT_VARINT; - break; - - case PB_LTYPE_FIXED32: - wiretype = PB_WT_32BIT; - break; - - case PB_LTYPE_FIXED64: - wiretype = PB_WT_64BIT; - break; - - case PB_LTYPE_BYTES: - case PB_LTYPE_STRING: - case PB_LTYPE_SUBMESSAGE: - wiretype = PB_WT_STRING; - break; - - default: - PB_RETURN_ERROR(stream, "invalid field type"); - } - - return pb_encode_tag(stream, wiretype, field->tag); -} - -bool checkreturn pb_encode_string(pb_ostream_t *stream, const uint8_t *buffer, size_t size) -{ - if (!pb_encode_varint(stream, (uint64_t)size)) - return false; - - return pb_write(stream, buffer, size); -} - -bool checkreturn pb_encode_submessage(pb_ostream_t *stream, const pb_field_t fields[], const void *src_struct) -{ - /* First calculate the message size using a non-writing substream. */ - pb_ostream_t substream = PB_OSTREAM_SIZING; - size_t size; - bool status; - - if (!pb_encode(&substream, fields, src_struct)) - { -#ifndef PB_NO_ERRMSG - stream->errmsg = substream.errmsg; -#endif - return false; - } - - size = substream.bytes_written; - - if (!pb_encode_varint(stream, (uint64_t)size)) - return false; - - if (stream->callback == NULL) - return pb_write(stream, NULL, size); /* Just sizing */ - - if (stream->bytes_written + size > stream->max_size) - PB_RETURN_ERROR(stream, "stream full"); - - /* Use a substream to verify that a callback doesn't write more than - * what it did the first time. */ - substream.callback = stream->callback; - substream.state = stream->state; - substream.max_size = size; - substream.bytes_written = 0; -#ifndef PB_NO_ERRMSG - substream.errmsg = NULL; -#endif - - status = pb_encode(&substream, fields, src_struct); - - stream->bytes_written += substream.bytes_written; - stream->state = substream.state; -#ifndef PB_NO_ERRMSG - stream->errmsg = substream.errmsg; -#endif - - if (substream.bytes_written != size) - PB_RETURN_ERROR(stream, "submsg size changed"); - - return status; -} - -/* Field encoders */ - -static bool checkreturn pb_enc_varint(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - int64_t value = 0; - - /* Cases 1 and 2 are for compilers that have smaller types for bool - * or enums. */ - switch (field->data_size) - { - case 1: value = *(const int8_t*)src; break; - case 2: value = *(const int16_t*)src; break; - case 4: value = *(const int32_t*)src; break; - case 8: value = *(const int64_t*)src; break; - default: PB_RETURN_ERROR(stream, "invalid data_size"); - } - - return pb_encode_varint(stream, (uint64_t)value); -} - -static bool checkreturn pb_enc_uvarint(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - uint64_t value = 0; - - switch (field->data_size) - { - case 4: value = *(const uint32_t*)src; break; - case 8: value = *(const uint64_t*)src; break; - default: PB_RETURN_ERROR(stream, "invalid data_size"); - } - - return pb_encode_varint(stream, value); -} - -static bool checkreturn pb_enc_svarint(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - int64_t value = 0; - - switch (field->data_size) - { - case 4: value = *(const int32_t*)src; break; - case 8: value = *(const int64_t*)src; break; - default: PB_RETURN_ERROR(stream, "invalid data_size"); - } - - return pb_encode_svarint(stream, value); -} - -static bool checkreturn pb_enc_fixed64(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - UNUSED(field); - return pb_encode_fixed64(stream, src); -} - -static bool checkreturn pb_enc_fixed32(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - UNUSED(field); - return pb_encode_fixed32(stream, src); -} - -static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - const pb_bytes_array_t *bytes = (const pb_bytes_array_t*)src; - - if (src == NULL) - { - /* Threat null pointer as an empty bytes field */ - return pb_encode_string(stream, NULL, 0); - } - - if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && - PB_BYTES_ARRAY_T_ALLOCSIZE(bytes->size) > field->data_size) - { - PB_RETURN_ERROR(stream, "bytes size exceeded"); - } - - return pb_encode_string(stream, bytes->bytes, bytes->size); -} - -static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - /* strnlen() is not always available, so just use a loop */ - size_t size = 0; - size_t max_size = field->data_size; - const char *p = (const char*)src; - - if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) - max_size = (size_t)-1; - - if (src == NULL) - { - size = 0; /* Threat null pointer as an empty string */ - } - else - { - while (size < max_size && *p != '\0') - { - size++; - p++; - } - } - - return pb_encode_string(stream, (const uint8_t*)src, size); -} - -static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_t *field, const void *src) -{ - if (field->ptr == NULL) - PB_RETURN_ERROR(stream, "invalid field descriptor"); - - return pb_encode_submessage(stream, (const pb_field_t*)field->ptr, src); -} - From 31bb13636f646a1ea3de4f560de45dd9b33ffdbb Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 25 Jan 2023 16:19:47 +0100 Subject: [PATCH 83/94] update fri msg generated files --- fri_client/src/FRIMessages.pb.c | 207 ++++-------- fri_client/src/FRIMessages.pb.h | 476 +++++++++++++++++++++------- fri_client/src/friUdpConnection.cpp | 2 +- 3 files changed, 435 insertions(+), 250 deletions(-) diff --git a/fri_client/src/FRIMessages.pb.c b/fri_client/src/FRIMessages.pb.c index 4fa7ee2a..e6700e55 100644 --- a/fri_client/src/FRIMessages.pb.c +++ b/fri_client/src/FRIMessages.pb.c @@ -1,151 +1,72 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.2.8 at Tue Feb 14 12:42:03 2017. */ - -#include - - - -const pb_msgdesc_t JointValues_fields[2] = { - PB_FIELD2( 1, DOUBLE , REPEATED, CALLBACK, FIRST, JointValues, value, value, 0), - PB_LAST_FIELD -}; - -const pb_sm TimeStamp_fields[3] = { - PB_FIELD2( 1, UINT32 , REQUIRED, STATIC , FIRST, TimeStamp, sec, sec, 0), - PB_FIELD2( 2, UINT32 , REQUIRED, STATIC , OTHER, TimeStamp, nanosec, sec, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t CartesianVector_fields[2] = { - PB_FIELD2( 1, DOUBLE , REPEATED, STATIC , FIRST, CartesianVector, element, element, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t Checksum_fields[2] = { - PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, Checksum, crc32, crc32, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t Transformation_fields[4] = { - PB_FIELD2( 1, STRING , REQUIRED, STATIC , FIRST, Transformation, name, name, 0), - PB_FIELD2( 2, DOUBLE , REPEATED, STATIC , OTHER, Transformation, matrix, name, 0), - PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, Transformation, timestamp, matrix, &TimeStamp_fields), - PB_LAST_FIELD -}; - -const pb_msgdesc_t FriIOValue_fields[6] = { - PB_FIELD2( 1, STRING , REQUIRED, STATIC , FIRST, FriIOValue, name, name, 0), - PB_FIELD2( 2, ENUM , REQUIRED, STATIC , OTHER, FriIOValue, type, name, 0), - PB_FIELD2( 3, ENUM , REQUIRED, STATIC , OTHER, FriIOValue, direction, type, 0), - PB_FIELD2( 4, UINT64 , OPTIONAL, STATIC , OTHER, FriIOValue, digitalValue, direction, 0), - PB_FIELD2( 5, DOUBLE , OPTIONAL, STATIC , OTHER, FriIOValue, analogValue, digitalValue, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t MessageHeader_fields[4] = { - PB_FIELD2( 1, UINT32 , REQUIRED, STATIC , FIRST, MessageHeader, messageIdentifier, messageIdentifier, 0), - PB_FIELD2( 2, UINT32 , REQUIRED, STATIC , OTHER, MessageHeader, sequenceCounter, messageIdentifier, 0), - PB_FIELD2( 3, UINT32 , REQUIRED, STATIC , OTHER, MessageHeader, reflectedSequenceCounter, sequenceCounter, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t ConnectionInfo_fields[5] = { - PB_FIELD2( 1, ENUM , REQUIRED, STATIC , FIRST, ConnectionInfo, sessionState, sessionState, 0), - PB_FIELD2( 2, ENUM , REQUIRED, STATIC , OTHER, ConnectionInfo, quality, sessionState, 0), - PB_FIELD2( 3, UINT32 , OPTIONAL, STATIC , OTHER, ConnectionInfo, sendPeriod, quality, 0), - PB_FIELD2( 4, UINT32 , OPTIONAL, STATIC , OTHER, ConnectionInfo, receiveMultiplier, sendPeriod, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t RobotInfo_fields[6] = { - PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, RobotInfo, numberOfJoints, numberOfJoints, 0), - PB_FIELD2( 2, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, safetyState, numberOfJoints, 0), - PB_FIELD2( 5, ENUM , REPEATED, CALLBACK, OTHER, RobotInfo, driveState, safetyState, 0), - PB_FIELD2( 6, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, operationMode, driveState, 0), - PB_FIELD2( 7, ENUM , OPTIONAL, STATIC , OTHER, RobotInfo, controlMode, operationMode, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t MessageMonitorData_fields[8] = { - PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageMonitorData, measuredJointPosition, measuredJointPosition, &JointValues_fields), - PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, measuredTorque, measuredJointPosition, &JointValues_fields), - PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, commandedJointPosition, measuredTorque, &JointValues_fields), - PB_FIELD2( 4, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, commandedTorque, commandedJointPosition, &JointValues_fields), - PB_FIELD2( 5, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, externalTorque, commandedTorque, &JointValues_fields), - PB_FIELD2( 8, MESSAGE , REPEATED, STATIC , OTHER, MessageMonitorData, readIORequest, externalTorque, &FriIOValue_fields), - PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, MessageMonitorData, timestamp, readIORequest, &TimeStamp_fields), - PB_LAST_FIELD -}; - -const pb_msgdesc_t MessageIpoData_fields[5] = { - PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageIpoData, jointPosition, jointPosition, &JointValues_fields), - PB_FIELD2( 10, ENUM , OPTIONAL, STATIC , OTHER, MessageIpoData, clientCommandMode, jointPosition, 0), - PB_FIELD2( 11, ENUM , OPTIONAL, STATIC , OTHER, MessageIpoData, overlayType, clientCommandMode, 0), - PB_FIELD2( 12, DOUBLE , OPTIONAL, STATIC , OTHER, MessageIpoData, trackingPerformance, overlayType, 0), - PB_LAST_FIELD -}; - -const pb_msgdesc_t MessageCommandData_fields[6] = { - PB_FIELD2( 1, MESSAGE , OPTIONAL, STATIC , FIRST, MessageCommandData, jointPosition, jointPosition, &JointValues_fields), - PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageCommandData, cartesianWrenchFeedForward, jointPosition, &CartesianVector_fields), - PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, MessageCommandData, jointTorque, cartesianWrenchFeedForward, &JointValues_fields), - PB_FIELD2( 4, MESSAGE , REPEATED, STATIC , OTHER, MessageCommandData, commandedTransformations, jointTorque, &Transformation_fields), - PB_FIELD2( 5, MESSAGE , REPEATED, STATIC , OTHER, MessageCommandData, writeIORequest, commandedTransformations, &FriIOValue_fields), - PB_LAST_FIELD -}; - -const pb_msgdesc_t MessageEndOf_fields[3] = { - PB_FIELD2( 1, INT32 , OPTIONAL, STATIC , FIRST, MessageEndOf, messageLength, messageLength, 0), - PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, MessageEndOf, messageChecksum, messageLength, &Checksum_fields), - PB_LAST_FIELD -}; - -const pb_msgdesc_t FRIMonitoringMessage_fields[8] = { - PB_FIELD2( 1, MESSAGE , REQUIRED, STATIC , FIRST, FRIMonitoringMessage, header, header, &MessageHeader_fields), - PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, robotInfo, header, &RobotInfo_fields), - PB_FIELD2( 3, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, monitorData, robotInfo, &MessageMonitorData_fields), - PB_FIELD2( 4, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, connectionInfo, monitorData, &ConnectionInfo_fields), - PB_FIELD2( 5, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, ipoData, connectionInfo, &MessageIpoData_fields), - PB_FIELD2( 6, MESSAGE , REPEATED, STATIC , OTHER, FRIMonitoringMessage, requestedTransformations, ipoData, &Transformation_fields), - PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, FRIMonitoringMessage, endOfMessageData, requestedTransformations, &MessageEndOf_fields), - PB_LAST_FIELD -}; - -const pb_msgdesc_t FRICommandMessage_fields[4] = { - PB_FIELD2( 1, MESSAGE , REQUIRED, STATIC , FIRST, FRICommandMessage, header, header, &MessageHeader_fields), - PB_FIELD2( 2, MESSAGE , OPTIONAL, STATIC , OTHER, FRICommandMessage, commandData, header, &MessageCommandData_fields), - PB_FIELD2( 15, MESSAGE , OPTIONAL, STATIC , OTHER, FRICommandMessage, endOfMessageData, commandData, &MessageEndOf_fields), - PB_LAST_FIELD -}; - - -/* Check that field information fits in pb_msgdesc_t */ -#if !defined(PB_FIELD_32BIT) -/* If you get an error here, it means that you need to define PB_FIELD_32BIT - * compile-time option. You can do that in pb.h or on compiler command line. - * - * The reason you need to do this is that some of your messages contain tag - * numbers or field sizes that are larger than what can fit in 8 or 16 bit - * field descriptors. - */ -STATIC_ASSERT((pb_membersize(Transformation, timestamp) < 65536 && pb_membersize(MessageMonitorData, measuredJointPosition) < 65536 && pb_membersize(MessageMonitorData, measuredTorque) < 65536 && pb_membersize(MessageMonitorData, commandedJointPosition) < 65536 && pb_membersize(MessageMonitorData, commandedTorque) < 65536 && pb_membersize(MessageMonitorData, externalTorque) < 65536 && pb_membersize(MessageMonitorData, readIORequest[0]) < 65536 && pb_membersize(MessageMonitorData, timestamp) < 65536 && pb_membersize(MessageIpoData, jointPosition) < 65536 && pb_membersize(MessageCommandData, jointPosition) < 65536 && pb_membersize(MessageCommandData, cartesianWrenchFeedForward) < 65536 && pb_membersize(MessageCommandData, jointTorque) < 65536 && pb_membersize(MessageCommandData, commandedTransformations[0]) < 65536 && pb_membersize(MessageCommandData, writeIORequest[0]) < 65536 && pb_membersize(MessageEndOf, messageChecksum) < 65536 && pb_membersize(FRIMonitoringMessage, header) < 65536 && pb_membersize(FRIMonitoringMessage, connectionInfo) < 65536 && pb_membersize(FRIMonitoringMessage, robotInfo) < 65536 && pb_membersize(FRIMonitoringMessage, monitorData) < 65536 && pb_membersize(FRIMonitoringMessage, ipoData) < 65536 && pb_membersize(FRIMonitoringMessage, requestedTransformations[0]) < 65536 && pb_membersize(FRIMonitoringMessage, endOfMessageData) < 65536 && pb_membersize(FRICommandMessage, header) < 65536 && pb_membersize(FRICommandMessage, commandData) < 65536 && pb_membersize(FRICommandMessage, endOfMessageData) < 65536), YOU_MUST_DEFINE_PB_FIELD_32BIT_FOR_MESSAGES_JointValues_TimeStamp_CartesianVector_Checksum_Transformation_FriIOValue_MessageHeader_ConnectionInfo_RobotInfo_MessageMonitorData_MessageIpoData_MessageCommandData_MessageEndOf_FRIMonitoringMessage_FRICommandMessage) -#endif +/* Generated by nanopb-0.4.8-dev */ -#if !defined(PB_FIELD_16BIT) && !defined(PB_FIELD_32BIT) -/* If you get an error here, it means that you need to define PB_FIELD_16BIT - * compile-time option. You can do that in pb.h or on compiler command line. - * - * The reason you need to do this is that some of your messages contain tag - * numbers or field sizes that are larger than what can fit in the default - * 8 bit descriptors. - */ -STATIC_ASSERT((pb_membersize(Transformation, timestamp) < 256 && pb_membersize(MessageMonitorData, measuredJointPosition) < 256 && pb_membersize(MessageMonitorData, measuredTorque) < 256 && pb_membersize(MessageMonitorData, commandedJointPosition) < 256 && pb_membersize(MessageMonitorData, commandedTorque) < 256 && pb_membersize(MessageMonitorData, externalTorque) < 256 && pb_membersize(MessageMonitorData, readIORequest[0]) < 256 && pb_membersize(MessageMonitorData, timestamp) < 256 && pb_membersize(MessageIpoData, jointPosition) < 256 && pb_membersize(MessageCommandData, jointPosition) < 256 && pb_membersize(MessageCommandData, cartesianWrenchFeedForward) < 256 && pb_membersize(MessageCommandData, jointTorque) < 256 && pb_membersize(MessageCommandData, commandedTransformations[0]) < 256 && pb_membersize(MessageCommandData, writeIORequest[0]) < 256 && pb_membersize(MessageEndOf, messageChecksum) < 256 && pb_membersize(FRIMonitoringMessage, header) < 256 && pb_membersize(FRIMonitoringMessage, connectionInfo) < 256 && pb_membersize(FRIMonitoringMessage, robotInfo) < 256 && pb_membersize(FRIMonitoringMessage, monitorData) < 256 && pb_membersize(FRIMonitoringMessage, ipoData) < 256 && pb_membersize(FRIMonitoringMessage, requestedTransformations[0]) < 256 && pb_membersize(FRIMonitoringMessage, endOfMessageData) < 256 && pb_membersize(FRICommandMessage, header) < 256 && pb_membersize(FRICommandMessage, commandData) < 256 && pb_membersize(FRICommandMessage, endOfMessageData) < 256), YOU_MUST_DEFINE_PB_FIELD_16BIT_FOR_MESSAGES_JointValues_TimeStamp_CartesianVector_Checksum_Transformation_FriIOValue_MessageHeader_ConnectionInfo_RobotInfo_MessageMonitorData_MessageIpoData_MessageCommandData_MessageEndOf_FRIMonitoringMessage_FRICommandMessage) +#include "FRIMessages.pb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. #endif +PB_BIND(JointValues, JointValues, AUTO) + + +PB_BIND(TimeStamp, TimeStamp, AUTO) + + +PB_BIND(CartesianVector, CartesianVector, AUTO) + + +PB_BIND(Checksum, Checksum, AUTO) + + +PB_BIND(Transformation, Transformation, AUTO) + + +PB_BIND(FriIOValue, FriIOValue, AUTO) + + +PB_BIND(MessageHeader, MessageHeader, AUTO) + + +PB_BIND(ConnectionInfo, ConnectionInfo, AUTO) + + +PB_BIND(RobotInfo, RobotInfo, AUTO) + + +PB_BIND(MessageMonitorData, MessageMonitorData, 2) + +PB_BIND(MessageIpoData, MessageIpoData, AUTO) + + +PB_BIND(MessageCommandData, MessageCommandData, 2) + + +PB_BIND(MessageEndOf, MessageEndOf, AUTO) + + +PB_BIND(FRIMonitoringMessage, FRIMonitoringMessage, 2) + + +PB_BIND(FRICommandMessage, FRICommandMessage, 2) + + + + + + + + + + + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT /* On some platforms (such as AVR), double is really float. - * These are not directly supported by nanopb, but see example_avr_double. - * To get rid of this error, remove any double fields from your .proto. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. */ -STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif diff --git a/fri_client/src/FRIMessages.pb.h b/fri_client/src/FRIMessages.pb.h index 8c3344a7..57982d00 100644 --- a/fri_client/src/FRIMessages.pb.h +++ b/fri_client/src/FRIMessages.pb.h @@ -1,12 +1,12 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.2.8 at Tue Feb 14 12:42:03 2017. */ +/* Generated by nanopb-0.4.8-dev */ -#ifndef _PB_FRIMESSAGES_PB_H_ -#define _PB_FRIMESSAGES_PB_H_ +#ifndef PB_FRIMESSAGES_PB_H_INCLUDED +#define PB_FRIMESSAGES_PB_H_INCLUDED #include -#ifdef __cplusplus -extern "C" { +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. #endif /* Enum definitions */ @@ -76,8 +76,17 @@ typedef enum _FriIODirection { } FriIODirection; /* Struct definitions */ +typedef struct _JointValues { + pb_callback_t value; +} JointValues; + +typedef struct _TimeStamp { + uint32_t sec; + uint32_t nanosec; +} TimeStamp; + typedef struct _CartesianVector { - size_t element_count; + pb_size_t element_count; double element[6]; } CartesianVector; @@ -86,14 +95,13 @@ typedef struct _Checksum { int32_t crc32; } Checksum; -typedef struct _ConnectionInfo { - FRISessionState sessionState; - FRIConnectionQuality quality; - bool has_sendPeriod; - uint32_t sendPeriod; - bool has_receiveMultiplier; - uint32_t receiveMultiplier; -} ConnectionInfo; +typedef struct _Transformation { + char name[64]; + pb_size_t matrix_count; + double matrix[12]; + bool has_timestamp; + TimeStamp timestamp; +} Transformation; typedef struct _FriIOValue { char name[64]; @@ -105,16 +113,21 @@ typedef struct _FriIOValue { double analogValue; } FriIOValue; -typedef struct _JointValues { - pb_callback_t value; -} JointValues; - typedef struct _MessageHeader { uint32_t messageIdentifier; uint32_t sequenceCounter; uint32_t reflectedSequenceCounter; } MessageHeader; +typedef struct _ConnectionInfo { + FRISessionState sessionState; + FRIConnectionQuality quality; + bool has_sendPeriod; + uint32_t sendPeriod; + bool has_receiveMultiplier; + uint32_t receiveMultiplier; +} ConnectionInfo; + typedef struct _RobotInfo { bool has_numberOfJoints; int32_t numberOfJoints; @@ -127,29 +140,6 @@ typedef struct _RobotInfo { ControlMode controlMode; } RobotInfo; -typedef struct _TimeStamp { - uint32_t sec; - uint32_t nanosec; -} TimeStamp; - -typedef struct _MessageEndOf { - bool has_messageLength; - int32_t messageLength; - bool has_messageChecksum; - Checksum messageChecksum; -} MessageEndOf; - -typedef struct _MessageIpoData { - bool has_jointPosition; - JointValues jointPosition; - bool has_clientCommandMode; - ClientCommandMode clientCommandMode; - bool has_overlayType; - OverlayType overlayType; - bool has_trackingPerformance; - double trackingPerformance; -} MessageIpoData; - typedef struct _MessageMonitorData { bool has_measuredJointPosition; JointValues measuredJointPosition; @@ -161,19 +151,42 @@ typedef struct _MessageMonitorData { JointValues commandedTorque; bool has_externalTorque; JointValues externalTorque; - size_t readIORequest_count; + pb_size_t readIORequest_count; FriIOValue readIORequest[10]; bool has_timestamp; TimeStamp timestamp; } MessageMonitorData; -typedef struct _Transformation { - char name[64]; - size_t matrix_count; - double matrix[12]; - bool has_timestamp; - TimeStamp timestamp; -} Transformation; +typedef struct _MessageIpoData { + bool has_jointPosition; + JointValues jointPosition; + bool has_clientCommandMode; + ClientCommandMode clientCommandMode; + bool has_overlayType; + OverlayType overlayType; + bool has_trackingPerformance; + double trackingPerformance; +} MessageIpoData; + +typedef struct _MessageCommandData { + bool has_jointPosition; + JointValues jointPosition; + bool has_cartesianWrenchFeedForward; + CartesianVector cartesianWrenchFeedForward; + bool has_jointTorque; + JointValues jointTorque; + pb_size_t commandedTransformations_count; + Transformation commandedTransformations[5]; + pb_size_t writeIORequest_count; + FriIOValue writeIORequest[10]; +} MessageCommandData; + +typedef struct _MessageEndOf { + bool has_messageLength; + int32_t messageLength; + bool has_messageChecksum; + Checksum messageChecksum; +} MessageEndOf; typedef struct _FRIMonitoringMessage { MessageHeader header; @@ -185,25 +198,12 @@ typedef struct _FRIMonitoringMessage { ConnectionInfo connectionInfo; bool has_ipoData; MessageIpoData ipoData; - size_t requestedTransformations_count; + pb_size_t requestedTransformations_count; Transformation requestedTransformations[5]; bool has_endOfMessageData; MessageEndOf endOfMessageData; } FRIMonitoringMessage; -typedef struct _MessageCommandData { - bool has_jointPosition; - JointValues jointPosition; - bool has_cartesianWrenchFeedForward; - CartesianVector cartesianWrenchFeedForward; - bool has_jointTorque; - JointValues jointTorque; - size_t commandedTransformations_count; - Transformation commandedTransformations[5]; - size_t writeIORequest_count; - FriIOValue writeIORequest[10]; -} MessageCommandData; - typedef struct _FRICommandMessage { MessageHeader header; bool has_commandData; @@ -212,37 +212,136 @@ typedef struct _FRICommandMessage { MessageEndOf endOfMessageData; } FRICommandMessage; -/* Default values for struct fields */ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Helper constants for enums */ +#define _FRISessionState_MIN FRISessionState_IDLE +#define _FRISessionState_MAX FRISessionState_COMMANDING_ACTIVE +#define _FRISessionState_ARRAYSIZE ((FRISessionState)(FRISessionState_COMMANDING_ACTIVE+1)) + +#define _FRIConnectionQuality_MIN FRIConnectionQuality_POOR +#define _FRIConnectionQuality_MAX FRIConnectionQuality_EXCELLENT +#define _FRIConnectionQuality_ARRAYSIZE ((FRIConnectionQuality)(FRIConnectionQuality_EXCELLENT+1)) + +#define _SafetyState_MIN SafetyState_NORMAL_OPERATION +#define _SafetyState_MAX SafetyState_SAFETY_STOP_LEVEL_2 +#define _SafetyState_ARRAYSIZE ((SafetyState)(SafetyState_SAFETY_STOP_LEVEL_2+1)) + +#define _OperationMode_MIN OperationMode_TEST_MODE_1 +#define _OperationMode_MAX OperationMode_AUTOMATIC_MODE +#define _OperationMode_ARRAYSIZE ((OperationMode)(OperationMode_AUTOMATIC_MODE+1)) + +#define _DriveState_MIN DriveState_OFF +#define _DriveState_MAX DriveState_ACTIVE +#define _DriveState_ARRAYSIZE ((DriveState)(DriveState_ACTIVE+1)) + +#define _ControlMode_MIN ControlMode_POSITION_CONTROLMODE +#define _ControlMode_MAX ControlMode_NO_CONTROLMODE +#define _ControlMode_ARRAYSIZE ((ControlMode)(ControlMode_NO_CONTROLMODE+1)) + +#define _ClientCommandMode_MIN ClientCommandMode_NO_COMMAND_MODE +#define _ClientCommandMode_MAX ClientCommandMode_TORQUE +#define _ClientCommandMode_ARRAYSIZE ((ClientCommandMode)(ClientCommandMode_TORQUE+1)) + +#define _OverlayType_MIN OverlayType_NO_OVERLAY +#define _OverlayType_MAX OverlayType_CARTESIAN +#define _OverlayType_ARRAYSIZE ((OverlayType)(OverlayType_CARTESIAN+1)) + +#define _FriIOType_MIN FriIOType_BOOLEAN +#define _FriIOType_MAX FriIOType_ANALOG +#define _FriIOType_ARRAYSIZE ((FriIOType)(FriIOType_ANALOG+1)) + +#define _FriIODirection_MIN FriIODirection_INPUT +#define _FriIODirection_MAX FriIODirection_OUTPUT +#define _FriIODirection_ARRAYSIZE ((FriIODirection)(FriIODirection_OUTPUT+1)) + + + + + + +#define FriIOValue_type_ENUMTYPE FriIOType +#define FriIOValue_direction_ENUMTYPE FriIODirection + + +#define ConnectionInfo_sessionState_ENUMTYPE FRISessionState +#define ConnectionInfo_quality_ENUMTYPE FRIConnectionQuality + +#define RobotInfo_safetyState_ENUMTYPE SafetyState +#define RobotInfo_driveState_ENUMTYPE DriveState +#define RobotInfo_operationMode_ENUMTYPE OperationMode +#define RobotInfo_controlMode_ENUMTYPE ControlMode + + +#define MessageIpoData_clientCommandMode_ENUMTYPE ClientCommandMode +#define MessageIpoData_overlayType_ENUMTYPE OverlayType + + + + + + +/* Initializer values for message structs */ +#define JointValues_init_default {{{NULL}, NULL}} +#define TimeStamp_init_default {0, 0} +#define CartesianVector_init_default {0, {0, 0, 0, 0, 0, 0}} +#define Checksum_init_default {false, 0} +#define Transformation_init_default {"", 0, {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, false, TimeStamp_init_default} +#define FriIOValue_init_default {"", _FriIOType_MIN, _FriIODirection_MIN, false, 0, false, 0} +#define MessageHeader_init_default {0, 0, 0} +#define ConnectionInfo_init_default {_FRISessionState_MIN, _FRIConnectionQuality_MIN, false, 0, false, 0} +#define RobotInfo_init_default {false, 0, false, _SafetyState_MIN, {{NULL}, NULL}, false, _OperationMode_MIN, false, _ControlMode_MIN} +#define MessageMonitorData_init_default {false, JointValues_init_default, false, JointValues_init_default, false, JointValues_init_default, false, JointValues_init_default, false, JointValues_init_default, 0, {FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default}, false, TimeStamp_init_default} +#define MessageIpoData_init_default {false, JointValues_init_default, false, _ClientCommandMode_MIN, false, _OverlayType_MIN, false, 0} +#define MessageCommandData_init_default {false, JointValues_init_default, false, CartesianVector_init_default, false, JointValues_init_default, 0, {Transformation_init_default, Transformation_init_default, Transformation_init_default, Transformation_init_default, Transformation_init_default}, 0, {FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default, FriIOValue_init_default}} +#define MessageEndOf_init_default {false, 0, false, Checksum_init_default} +#define FRIMonitoringMessage_init_default {MessageHeader_init_default, false, RobotInfo_init_default, false, MessageMonitorData_init_default, false, ConnectionInfo_init_default, false, MessageIpoData_init_default, 0, {Transformation_init_default, Transformation_init_default, Transformation_init_default, Transformation_init_default, Transformation_init_default}, false, MessageEndOf_init_default} +#define FRICommandMessage_init_default {MessageHeader_init_default, false, MessageCommandData_init_default, false, MessageEndOf_init_default} +#define JointValues_init_zero {{{NULL}, NULL}} +#define TimeStamp_init_zero {0, 0} +#define CartesianVector_init_zero {0, {0, 0, 0, 0, 0, 0}} +#define Checksum_init_zero {false, 0} +#define Transformation_init_zero {"", 0, {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, false, TimeStamp_init_zero} +#define FriIOValue_init_zero {"", _FriIOType_MIN, _FriIODirection_MIN, false, 0, false, 0} +#define MessageHeader_init_zero {0, 0, 0} +#define ConnectionInfo_init_zero {_FRISessionState_MIN, _FRIConnectionQuality_MIN, false, 0, false, 0} +#define RobotInfo_init_zero {false, 0, false, _SafetyState_MIN, {{NULL}, NULL}, false, _OperationMode_MIN, false, _ControlMode_MIN} +#define MessageMonitorData_init_zero {false, JointValues_init_zero, false, JointValues_init_zero, false, JointValues_init_zero, false, JointValues_init_zero, false, JointValues_init_zero, 0, {FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero}, false, TimeStamp_init_zero} +#define MessageIpoData_init_zero {false, JointValues_init_zero, false, _ClientCommandMode_MIN, false, _OverlayType_MIN, false, 0} +#define MessageCommandData_init_zero {false, JointValues_init_zero, false, CartesianVector_init_zero, false, JointValues_init_zero, 0, {Transformation_init_zero, Transformation_init_zero, Transformation_init_zero, Transformation_init_zero, Transformation_init_zero}, 0, {FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero, FriIOValue_init_zero}} +#define MessageEndOf_init_zero {false, 0, false, Checksum_init_zero} +#define FRIMonitoringMessage_init_zero {MessageHeader_init_zero, false, RobotInfo_init_zero, false, MessageMonitorData_init_zero, false, ConnectionInfo_init_zero, false, MessageIpoData_init_zero, 0, {Transformation_init_zero, Transformation_init_zero, Transformation_init_zero, Transformation_init_zero, Transformation_init_zero}, false, MessageEndOf_init_zero} +#define FRICommandMessage_init_zero {MessageHeader_init_zero, false, MessageCommandData_init_zero, false, MessageEndOf_init_zero} /* Field tags (for use in manual encoding/decoding) */ +#define JointValues_value_tag 1 +#define TimeStamp_sec_tag 1 +#define TimeStamp_nanosec_tag 2 #define CartesianVector_element_tag 1 #define Checksum_crc32_tag 1 -#define ConnectionInfo_sessionState_tag 1 -#define ConnectionInfo_quality_tag 2 -#define ConnectionInfo_sendPeriod_tag 3 -#define ConnectionInfo_receiveMultiplier_tag 4 +#define Transformation_name_tag 1 +#define Transformation_matrix_tag 2 +#define Transformation_timestamp_tag 3 #define FriIOValue_name_tag 1 #define FriIOValue_type_tag 2 #define FriIOValue_direction_tag 3 #define FriIOValue_digitalValue_tag 4 #define FriIOValue_analogValue_tag 5 -#define JointValues_value_tag 1 #define MessageHeader_messageIdentifier_tag 1 #define MessageHeader_sequenceCounter_tag 2 #define MessageHeader_reflectedSequenceCounter_tag 3 +#define ConnectionInfo_sessionState_tag 1 +#define ConnectionInfo_quality_tag 2 +#define ConnectionInfo_sendPeriod_tag 3 +#define ConnectionInfo_receiveMultiplier_tag 4 #define RobotInfo_numberOfJoints_tag 1 #define RobotInfo_safetyState_tag 2 #define RobotInfo_driveState_tag 5 #define RobotInfo_operationMode_tag 6 #define RobotInfo_controlMode_tag 7 -#define TimeStamp_sec_tag 1 -#define TimeStamp_nanosec_tag 2 -#define MessageEndOf_messageLength_tag 1 -#define MessageEndOf_messageChecksum_tag 2 -#define MessageIpoData_jointPosition_tag 1 -#define MessageIpoData_clientCommandMode_tag 10 -#define MessageIpoData_overlayType_tag 11 -#define MessageIpoData_trackingPerformance_tag 12 #define MessageMonitorData_measuredJointPosition_tag 1 #define MessageMonitorData_measuredTorque_tag 2 #define MessageMonitorData_commandedJointPosition_tag 3 @@ -250,51 +349,216 @@ typedef struct _FRICommandMessage { #define MessageMonitorData_externalTorque_tag 5 #define MessageMonitorData_readIORequest_tag 8 #define MessageMonitorData_timestamp_tag 15 -#define Transformation_name_tag 1 -#define Transformation_matrix_tag 2 -#define Transformation_timestamp_tag 3 +#define MessageIpoData_jointPosition_tag 1 +#define MessageIpoData_clientCommandMode_tag 10 +#define MessageIpoData_overlayType_tag 11 +#define MessageIpoData_trackingPerformance_tag 12 +#define MessageCommandData_jointPosition_tag 1 +#define MessageCommandData_cartesianWrenchFeedForward_tag 2 +#define MessageCommandData_jointTorque_tag 3 +#define MessageCommandData_commandedTransformations_tag 4 +#define MessageCommandData_writeIORequest_tag 5 +#define MessageEndOf_messageLength_tag 1 +#define MessageEndOf_messageChecksum_tag 2 #define FRIMonitoringMessage_header_tag 1 -#define FRIMonitoringMessage_connectionInfo_tag 4 #define FRIMonitoringMessage_robotInfo_tag 2 #define FRIMonitoringMessage_monitorData_tag 3 +#define FRIMonitoringMessage_connectionInfo_tag 4 #define FRIMonitoringMessage_ipoData_tag 5 #define FRIMonitoringMessage_requestedTransformations_tag 6 #define FRIMonitoringMessage_endOfMessageData_tag 15 -#define MessageCommandData_jointPosition_tag 1 -#define MessageCommandData_cartesianWrenchFeedForward_tag 2 -#define MessageCommandData_jointTorque_tag 3 -#define MessageCommandData_commandedTransformations_tag 4 -#define MessageCommandData_writeIORequest_tag 5 #define FRICommandMessage_header_tag 1 #define FRICommandMessage_commandData_tag 2 #define FRICommandMessage_endOfMessageData_tag 15 /* Struct field encoding specification for nanopb */ -extern const pb_msgdesc_t JointValues_fields[2]; -extern const pb_msgdesc_t TimeStamp_fields[3]; -extern const pb_msgdesc_t CartesianVector_fields[2]; -extern const pb_msgdesc_t Checksum_fields[2]; -extern const pb_msgdesc_t Transformation_fields[4]; -extern const pb_msgdesc_t FriIOValue_fields[6]; -extern const pb_msgdesc_t MessageHeader_fields[4]; -extern const pb_msgdesc_t ConnectionInfo_fields[5]; -extern const pb_msgdesc_t RobotInfo_fields[6]; -extern const pb_msgdesc_t MessageMonitorData_fields[8]; -extern const pb_msgdesc_t MessageIpoData_fields[5]; -extern const pb_msgdesc_t MessageCommandData_fields[6]; -extern const pb_msgdesc_t MessageEndOf_fields[3]; -extern const pb_msgdesc_t FRIMonitoringMessage_fields[8]; -extern const pb_msgdesc_t FRICommandMessage_fields[4]; +#define JointValues_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, DOUBLE, value, 1) +#define JointValues_CALLBACK pb_default_field_callback +#define JointValues_DEFAULT NULL + +#define TimeStamp_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, UINT32, sec, 1) \ +X(a, STATIC, REQUIRED, UINT32, nanosec, 2) +#define TimeStamp_CALLBACK NULL +#define TimeStamp_DEFAULT NULL + +#define CartesianVector_FIELDLIST(X, a) \ +X(a, STATIC, REPEATED, DOUBLE, element, 1) +#define CartesianVector_CALLBACK NULL +#define CartesianVector_DEFAULT NULL + +#define Checksum_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, INT32, crc32, 1) +#define Checksum_CALLBACK NULL +#define Checksum_DEFAULT NULL + +#define Transformation_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, STRING, name, 1) \ +X(a, STATIC, REPEATED, DOUBLE, matrix, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, timestamp, 3) +#define Transformation_CALLBACK NULL +#define Transformation_DEFAULT NULL +#define Transformation_timestamp_MSGTYPE TimeStamp + +#define FriIOValue_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, STRING, name, 1) \ +X(a, STATIC, REQUIRED, UENUM, type, 2) \ +X(a, STATIC, REQUIRED, UENUM, direction, 3) \ +X(a, STATIC, OPTIONAL, UINT64, digitalValue, 4) \ +X(a, STATIC, OPTIONAL, DOUBLE, analogValue, 5) +#define FriIOValue_CALLBACK NULL +#define FriIOValue_DEFAULT NULL + +#define MessageHeader_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, UINT32, messageIdentifier, 1) \ +X(a, STATIC, REQUIRED, UINT32, sequenceCounter, 2) \ +X(a, STATIC, REQUIRED, UINT32, reflectedSequenceCounter, 3) +#define MessageHeader_CALLBACK NULL +#define MessageHeader_DEFAULT NULL + +#define ConnectionInfo_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, UENUM, sessionState, 1) \ +X(a, STATIC, REQUIRED, UENUM, quality, 2) \ +X(a, STATIC, OPTIONAL, UINT32, sendPeriod, 3) \ +X(a, STATIC, OPTIONAL, UINT32, receiveMultiplier, 4) +#define ConnectionInfo_CALLBACK NULL +#define ConnectionInfo_DEFAULT NULL + +#define RobotInfo_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, INT32, numberOfJoints, 1) \ +X(a, STATIC, OPTIONAL, UENUM, safetyState, 2) \ +X(a, CALLBACK, REPEATED, UENUM, driveState, 5) \ +X(a, STATIC, OPTIONAL, UENUM, operationMode, 6) \ +X(a, STATIC, OPTIONAL, UENUM, controlMode, 7) +#define RobotInfo_CALLBACK pb_default_field_callback +#define RobotInfo_DEFAULT NULL + +#define MessageMonitorData_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, MESSAGE, measuredJointPosition, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, measuredTorque, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, commandedJointPosition, 3) \ +X(a, STATIC, OPTIONAL, MESSAGE, commandedTorque, 4) \ +X(a, STATIC, OPTIONAL, MESSAGE, externalTorque, 5) \ +X(a, STATIC, REPEATED, MESSAGE, readIORequest, 8) \ +X(a, STATIC, OPTIONAL, MESSAGE, timestamp, 15) +#define MessageMonitorData_CALLBACK NULL +#define MessageMonitorData_DEFAULT NULL +#define MessageMonitorData_measuredJointPosition_MSGTYPE JointValues +#define MessageMonitorData_measuredTorque_MSGTYPE JointValues +#define MessageMonitorData_commandedJointPosition_MSGTYPE JointValues +#define MessageMonitorData_commandedTorque_MSGTYPE JointValues +#define MessageMonitorData_externalTorque_MSGTYPE JointValues +#define MessageMonitorData_readIORequest_MSGTYPE FriIOValue +#define MessageMonitorData_timestamp_MSGTYPE TimeStamp + +#define MessageIpoData_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, MESSAGE, jointPosition, 1) \ +X(a, STATIC, OPTIONAL, UENUM, clientCommandMode, 10) \ +X(a, STATIC, OPTIONAL, UENUM, overlayType, 11) \ +X(a, STATIC, OPTIONAL, DOUBLE, trackingPerformance, 12) +#define MessageIpoData_CALLBACK NULL +#define MessageIpoData_DEFAULT NULL +#define MessageIpoData_jointPosition_MSGTYPE JointValues + +#define MessageCommandData_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, MESSAGE, jointPosition, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, cartesianWrenchFeedForward, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, jointTorque, 3) \ +X(a, STATIC, REPEATED, MESSAGE, commandedTransformations, 4) \ +X(a, STATIC, REPEATED, MESSAGE, writeIORequest, 5) +#define MessageCommandData_CALLBACK NULL +#define MessageCommandData_DEFAULT NULL +#define MessageCommandData_jointPosition_MSGTYPE JointValues +#define MessageCommandData_cartesianWrenchFeedForward_MSGTYPE CartesianVector +#define MessageCommandData_jointTorque_MSGTYPE JointValues +#define MessageCommandData_commandedTransformations_MSGTYPE Transformation +#define MessageCommandData_writeIORequest_MSGTYPE FriIOValue + +#define MessageEndOf_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, INT32, messageLength, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, messageChecksum, 2) +#define MessageEndOf_CALLBACK NULL +#define MessageEndOf_DEFAULT NULL +#define MessageEndOf_messageChecksum_MSGTYPE Checksum + +#define FRIMonitoringMessage_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, MESSAGE, header, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, robotInfo, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, monitorData, 3) \ +X(a, STATIC, OPTIONAL, MESSAGE, connectionInfo, 4) \ +X(a, STATIC, OPTIONAL, MESSAGE, ipoData, 5) \ +X(a, STATIC, REPEATED, MESSAGE, requestedTransformations, 6) \ +X(a, STATIC, OPTIONAL, MESSAGE, endOfMessageData, 15) +#define FRIMonitoringMessage_CALLBACK NULL +#define FRIMonitoringMessage_DEFAULT NULL +#define FRIMonitoringMessage_header_MSGTYPE MessageHeader +#define FRIMonitoringMessage_robotInfo_MSGTYPE RobotInfo +#define FRIMonitoringMessage_monitorData_MSGTYPE MessageMonitorData +#define FRIMonitoringMessage_connectionInfo_MSGTYPE ConnectionInfo +#define FRIMonitoringMessage_ipoData_MSGTYPE MessageIpoData +#define FRIMonitoringMessage_requestedTransformations_MSGTYPE Transformation +#define FRIMonitoringMessage_endOfMessageData_MSGTYPE MessageEndOf + +#define FRICommandMessage_FIELDLIST(X, a) \ +X(a, STATIC, REQUIRED, MESSAGE, header, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, commandData, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, endOfMessageData, 15) +#define FRICommandMessage_CALLBACK NULL +#define FRICommandMessage_DEFAULT NULL +#define FRICommandMessage_header_MSGTYPE MessageHeader +#define FRICommandMessage_commandData_MSGTYPE MessageCommandData +#define FRICommandMessage_endOfMessageData_MSGTYPE MessageEndOf + +extern const pb_msgdesc_t JointValues_msg; +extern const pb_msgdesc_t TimeStamp_msg; +extern const pb_msgdesc_t CartesianVector_msg; +extern const pb_msgdesc_t Checksum_msg; +extern const pb_msgdesc_t Transformation_msg; +extern const pb_msgdesc_t FriIOValue_msg; +extern const pb_msgdesc_t MessageHeader_msg; +extern const pb_msgdesc_t ConnectionInfo_msg; +extern const pb_msgdesc_t RobotInfo_msg; +extern const pb_msgdesc_t MessageMonitorData_msg; +extern const pb_msgdesc_t MessageIpoData_msg; +extern const pb_msgdesc_t MessageCommandData_msg; +extern const pb_msgdesc_t MessageEndOf_msg; +extern const pb_msgdesc_t FRIMonitoringMessage_msg; +extern const pb_msgdesc_t FRICommandMessage_msg; + +/* Defines for backwards compatibility with code written before nanopb-0.4.0 */ +#define JointValues_fields &JointValues_msg +#define TimeStamp_fields &TimeStamp_msg +#define CartesianVector_fields &CartesianVector_msg +#define Checksum_fields &Checksum_msg +#define Transformation_fields &Transformation_msg +#define FriIOValue_fields &FriIOValue_msg +#define MessageHeader_fields &MessageHeader_msg +#define ConnectionInfo_fields &ConnectionInfo_msg +#define RobotInfo_fields &RobotInfo_msg +#define MessageMonitorData_fields &MessageMonitorData_msg +#define MessageIpoData_fields &MessageIpoData_msg +#define MessageCommandData_fields &MessageCommandData_msg +#define MessageEndOf_fields &MessageEndOf_msg +#define FRIMonitoringMessage_fields &FRIMonitoringMessage_msg +#define FRICommandMessage_fields &FRICommandMessage_msg /* Maximum encoded size of messages (where known) */ -#define TimeStamp_size 12 +/* JointValues_size depends on runtime parameters */ +/* RobotInfo_size depends on runtime parameters */ +/* MessageMonitorData_size depends on runtime parameters */ +/* MessageIpoData_size depends on runtime parameters */ +/* MessageCommandData_size depends on runtime parameters */ +/* FRIMonitoringMessage_size depends on runtime parameters */ +/* FRICommandMessage_size depends on runtime parameters */ #define CartesianVector_size 54 #define Checksum_size 11 -#define Transformation_size 188 -#define FriIOValue_size 98 -#define MessageHeader_size 18 -#define ConnectionInfo_size 24 +#define ConnectionInfo_size 16 +#define FriIOValue_size 89 #define MessageEndOf_size 24 +#define MessageHeader_size 18 +#define TimeStamp_size 12 +#define Transformation_size 187 #ifdef __cplusplus } /* extern "C" */ diff --git a/fri_client/src/friUdpConnection.cpp b/fri_client/src/friUdpConnection.cpp index 6558f1d3..c212354c 100644 --- a/fri_client/src/friUdpConnection.cpp +++ b/fri_client/src/friUdpConnection.cpp @@ -179,7 +179,7 @@ int UdpConnection::receive(char *buffer, int maxSize) #ifdef HAVE_SOCKLEN_T socklen_t sockAddrSize; #else - int sockAddrSize; + unsigned int sockAddrSize; #endif sockAddrSize = sizeof(struct sockaddr_in); /** check for timeout From 11562b59b5faa2748c21fc401833e9360cedb337 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 10:26:56 +0100 Subject: [PATCH 84/94] link protobuf lib to fri client --- fri_client/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fri_client/CMakeLists.txt b/fri_client/CMakeLists.txt index eccbf7ac..dfa052d2 100644 --- a/fri_client/CMakeLists.txt +++ b/fri_client/CMakeLists.txt @@ -49,7 +49,7 @@ file(GLOB private_headers src/pb_frimessages_callbacks.h ) -target_link_libraries(fri_client PRIVATE nanopb) +target_link_libraries(fri_client PRIVATE protobuf-nanopb) ament_export_targets(fri_client HAS_LIBRARY_TARGET) From bd527863a7f3ed64a6b26db7a929b90a32e13bd0 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 11:02:23 +0100 Subject: [PATCH 85/94] add is_configured check to control node --- .../src/kuka_sunrise/sunrise_control_node.cpp | 28 ++++++++++++------- 1 file changed, 18 insertions(+), 10 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 52d8153c..ac88e29b 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -28,22 +28,30 @@ int main(int argc, char ** argv) executor, "controller_manager"); - auto callback = [controller_manager](std_msgs::msg::Bool::SharedPtr) { - RCLCPP_INFO(controller_manager->get_logger(), "Robot manager node shut down, terminating"); - rclcpp::shutdown(); - }; - auto sub = - controller_manager->create_subscription("control_ended", 1, callback); + auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); + qos.best_effort(); + + std::atomic_bool is_configured = false; + auto is_configured_sub = controller_manager->create_subscription( + "robot_manager/is_configured", qos, + [&is_configured](std_msgs::msg::Bool::SharedPtr msg) { + is_configured = msg->data; + }); - std::thread control_loop([controller_manager]() { + std::thread control_loop([controller_manager, &is_configured]() { const rclcpp::Duration dt = rclcpp::Duration::from_seconds(1.0 / controller_manager->get_update_rate()); + std::chrono::milliseconds dt_ms {1000 / controller_manager->get_update_rate()}; while (rclcpp::ok()) { - controller_manager->read(controller_manager->now(), dt); - controller_manager->update(controller_manager->now(), dt); - controller_manager->write(controller_manager->now(), dt); + if (is_configured) { + controller_manager->read(controller_manager->now(), dt); + controller_manager->update(controller_manager->now(), dt); + controller_manager->write(controller_manager->now(), dt); + } else { + std::this_thread::sleep_for(dt_ms); + } } }); From c6a5afcaa12828893ad04cc4faf13ecd6dfba5b6 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 11:49:41 +0100 Subject: [PATCH 86/94] add configuring publisher to manager --- .../kuka_sunrise/robot_manager_node.hpp | 2 ++ .../src/kuka_sunrise/robot_manager_node.cpp | 21 ++++++++++++++++++- 2 files changed, 22 insertions(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp index e1e9bf1b..d6a8af42 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/robot_manager_node.hpp @@ -75,6 +75,8 @@ class RobotManagerNode : public kroshu_ros2_core::ROS2BaseLCNode, public Activat rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr command_state_changed_publisher_; + std::shared_ptr> is_configured_pub_; + std_msgs::msg::Bool is_configured_msg_; std::string controller_name_; void handleControlEndedError(); diff --git a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp index d42360f9..f2da04dd 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp @@ -50,6 +50,13 @@ RobotManagerNode::RobotManagerNode() "robot_manager/commanding_state_changed", qos); set_parameter_client_ = this->create_client( "configuration_manager/set_params", ::rmw_qos_profile_default, cbg_); + + auto is_configured_qos = rclcpp::QoS(rclcpp::KeepLast(1)); + is_configured_qos.best_effort(); + + is_configured_pub_ = this->create_publisher( + "robot_manager/is_configured", + is_configured_qos); } rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn @@ -87,7 +94,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) std::vector{"timing_controller", "robot_state_broadcaster"}; auto controller_response = kuka_sunrise::sendRequest( - change_controller_state_client_, controller_request, 0, 2000); + change_controller_state_client_, controller_request, 0, 3000); if (!controller_response || !controller_response->ok) { RCLCPP_ERROR(get_logger(), "Could not start controllers"); result = FAILURE; @@ -119,6 +126,11 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &) if (result != SUCCESS) { this->on_cleanup(get_current_state()); } + + is_configured_pub_->on_activate(); + is_configured_msg_.data = true; + is_configured_pub_->publish(is_configured_msg_); + return result; } @@ -160,6 +172,12 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &) return FAILURE; } + if (is_configured_pub_->is_activated()) { + is_configured_pub_->on_deactivate(); + is_configured_msg_.data = false; + is_configured_pub_->publish(is_configured_msg_); + } + return SUCCESS; } @@ -192,6 +210,7 @@ RobotManagerNode::on_shutdown(const rclcpp_lifecycle::State & state) } // TODO(Svastits): activation fails after deactivation +// TODO(Svastits): check if we have to send unconfigured msg to control node rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotManagerNode::on_activate(const rclcpp_lifecycle::State &) { From 4ca770c83f20888975d6554cd293355eb75a19ad Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 11:53:47 +0100 Subject: [PATCH 87/94] add temporary solution for block --- .../src/kuka_sunrise/sunrise_control_node.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index ac88e29b..5017057d 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -31,12 +31,12 @@ int main(int argc, char ** argv) auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); qos.best_effort(); - std::atomic_bool is_configured = false; - auto is_configured_sub = controller_manager->create_subscription( - "robot_manager/is_configured", qos, - [&is_configured](std_msgs::msg::Bool::SharedPtr msg) { - is_configured = msg->data; - }); + std::atomic_bool is_configured = true; + // auto is_configured_sub = controller_manager->create_subscription( + // "robot_manager/is_configured", qos, + // [&is_configured](std_msgs::msg::Bool::SharedPtr msg) { + // is_configured = msg->data; + // }); std::thread control_loop([controller_manager, &is_configured]() { @@ -46,6 +46,7 @@ int main(int argc, char ** argv) while (rclcpp::ok()) { if (is_configured) { + std::this_thread::sleep_for(std::chrono::milliseconds(1)); // TODO(Svastits): temporary workaround controller_manager->read(controller_manager->now(), dt); controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); From 074f1a9e476162e95f8c683a1a9c4d1dd1c1d392 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 12:07:08 +0100 Subject: [PATCH 88/94] fix cpplint --- kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp index 5017057d..4934e69c 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/sunrise_control_node.cpp @@ -46,7 +46,8 @@ int main(int argc, char ** argv) while (rclcpp::ok()) { if (is_configured) { - std::this_thread::sleep_for(std::chrono::milliseconds(1)); // TODO(Svastits): temporary workaround + // TODO(Svastits): temporary workaround + std::this_thread::sleep_for(std::chrono::milliseconds(1)); controller_manager->read(controller_manager->now(), dt); controller_manager->update(controller_manager->now(), dt); controller_manager->write(controller_manager->now(), dt); From 43f650d8319357abf2be3dc6678f826ab98ed001 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 12:27:34 +0100 Subject: [PATCH 89/94] rename kuka_sunrise_interfaces --- kuka_controllers/CMakeLists.txt | 4 ++-- .../kuka_controllers/robot_state_broadcaster.hpp | 6 +++--- .../include/kuka_controllers/timing_controller.hpp | 4 ++-- kuka_controllers/package.xml | 2 +- kuka_controllers/src/robot_state_broadcaster.cpp | 2 +- kuka_controllers/src/timing_controller.cpp | 6 +++--- kuka_driver_examples/robot_control/CMakeLists.txt | 10 +++++----- .../robot_control/interpolating_controller.hpp | 4 ++-- .../include/robot_control/joint_controller_base.hpp | 8 ++++---- .../include/robot_control/rate_scaled_controller.hpp | 6 +++--- kuka_driver_examples/robot_control/package.xml | 2 +- .../src/robot_control/joint_controller_base.cpp | 12 ++++++------ .../teleop_guided_robot/CMakeLists.txt | 4 ++-- .../include/control_system/system_manager.hpp | 4 ++-- kuka_driver_examples/teleop_guided_robot/package.xml | 2 +- .../src/control_system/system_manager.cpp | 6 +++--- .../CMakeLists.txt | 2 +- .../msg/RobotState.msg | 0 .../package.xml | 2 +- .../srv/GetState.srv | 0 .../srv/SetDouble.srv | 0 .../srv/SetInt.srv | 0 kuka_sunrise_driver/CMakeLists.txt | 10 +++++----- .../include/kuka_sunrise/configuration_manager.hpp | 4 ++-- .../kuka_sunrise/kuka_fri_hardware_interface.hpp | 4 ++-- kuka_sunrise_driver/package.xml | 2 +- .../src/kuka_sunrise/configuration_manager.cpp | 6 +++--- 27 files changed, 56 insertions(+), 56 deletions(-) rename {kuka_sunrise_interfaces => kuka_driver_interfaces}/CMakeLists.txt (95%) rename {kuka_sunrise_interfaces => kuka_driver_interfaces}/msg/RobotState.msg (100%) rename {kuka_sunrise_interfaces => kuka_driver_interfaces}/package.xml (95%) rename {kuka_sunrise_interfaces => kuka_driver_interfaces}/srv/GetState.srv (100%) rename {kuka_sunrise_interfaces => kuka_driver_interfaces}/srv/SetDouble.srv (100%) rename {kuka_sunrise_interfaces => kuka_driver_interfaces}/srv/SetInt.srv (100%) diff --git a/kuka_controllers/CMakeLists.txt b/kuka_controllers/CMakeLists.txt index 5aff87e8..3d0e3d76 100644 --- a/kuka_controllers/CMakeLists.txt +++ b/kuka_controllers/CMakeLists.txt @@ -10,7 +10,7 @@ find_package(controller_interface REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) -find_package(kuka_sunrise_interfaces REQUIRED) +find_package(kuka_driver_interfaces REQUIRED) include_directories(include) @@ -23,7 +23,7 @@ target_include_directories(${PROJECT_NAME} PRIVATE include ) -ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface std_msgs kuka_sunrise_interfaces +ament_target_dependencies(${PROJECT_NAME} rclcpp controller_interface std_msgs kuka_driver_interfaces ) pluginlib_export_plugin_description_file(controller_interface controller_plugins.xml) diff --git a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp index a8c06651..b3f2e85d 100644 --- a/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp +++ b/kuka_controllers/include/kuka_controllers/robot_state_broadcaster.hpp @@ -22,7 +22,7 @@ #include "controller_interface/controller_interface.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" -#include "kuka_sunrise_interfaces/msg/robot_state.hpp" +#include "kuka_driver_interfaces/msg/robot_state.hpp" #include "rclcpp/time.hpp" #include "rclcpp/duration.hpp" @@ -55,8 +55,8 @@ class RobotStateBroadcaster : public controller_interface::ControllerInterface private: int counter_ = 0; - rclcpp::Publisher::SharedPtr robot_state_publisher_; - kuka_sunrise_interfaces::msg::RobotState state_msg_; + rclcpp::Publisher::SharedPtr robot_state_publisher_; + kuka_driver_interfaces::msg::RobotState state_msg_; }; } // namespace kuka_controllers #endif // KUKA_CONTROLLERS__ROBOT_STATE_BROADCASTER_HPP_ diff --git a/kuka_controllers/include/kuka_controllers/timing_controller.hpp b/kuka_controllers/include/kuka_controllers/timing_controller.hpp index 7e99c8e2..16d2b6a0 100644 --- a/kuka_controllers/include/kuka_controllers/timing_controller.hpp +++ b/kuka_controllers/include/kuka_controllers/timing_controller.hpp @@ -24,7 +24,7 @@ #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp/time.hpp" #include "rclcpp/duration.hpp" -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "kuka_driver_interfaces/srv/set_int.hpp" #include "pluginlib/class_list_macros.hpp" @@ -53,7 +53,7 @@ class TimingController : public controller_interface::ControllerInterface controller_interface::CallbackReturn on_init() override; private: - rclcpp::Service::SharedPtr receive_multiplier_service_; + rclcpp::Service::SharedPtr receive_multiplier_service_; int receive_multiplier_ = 1; bool resend_multiplier_ = false; }; diff --git a/kuka_controllers/package.xml b/kuka_controllers/package.xml index 658fdbde..7606eab5 100644 --- a/kuka_controllers/package.xml +++ b/kuka_controllers/package.xml @@ -15,7 +15,7 @@ pluginlib rclcpp_lifecycle std_msgs - kuka_sunrise_interfaces + kuka_driver_interfaces ament_cmake diff --git a/kuka_controllers/src/robot_state_broadcaster.cpp b/kuka_controllers/src/robot_state_broadcaster.cpp index 0fbb3468..13ef9d88 100644 --- a/kuka_controllers/src/robot_state_broadcaster.cpp +++ b/kuka_controllers/src/robot_state_broadcaster.cpp @@ -18,7 +18,7 @@ namespace kuka_controllers { controller_interface::CallbackReturn RobotStateBroadcaster::on_init() { - robot_state_publisher_ = get_node()->create_publisher( + robot_state_publisher_ = get_node()->create_publisher( "robot_state", rclcpp::SystemDefaultsQoS()); return controller_interface::CallbackReturn::SUCCESS; } diff --git a/kuka_controllers/src/timing_controller.cpp b/kuka_controllers/src/timing_controller.cpp index 8a695ae0..aa368e9a 100644 --- a/kuka_controllers/src/timing_controller.cpp +++ b/kuka_controllers/src/timing_controller.cpp @@ -18,13 +18,13 @@ namespace kuka_controllers { controller_interface::CallbackReturn TimingController::on_init() { - auto callback = [this](kuka_sunrise_interfaces::srv::SetInt::Request::SharedPtr request, - kuka_sunrise_interfaces::srv::SetInt::Response::SharedPtr response) { + auto callback = [this](kuka_driver_interfaces::srv::SetInt::Request::SharedPtr request, + kuka_driver_interfaces::srv::SetInt::Response::SharedPtr response) { resend_multiplier_ = true; receive_multiplier_ = request->data; response->success = true; }; - receive_multiplier_service_ = get_node()->create_service( + receive_multiplier_service_ = get_node()->create_service( "set_receive_multiplier", callback); // TODO(Svastits): create service to get multiplier changes (or perpaps parameter??) // and set resend_multiplier_ to true in the callback diff --git a/kuka_driver_examples/robot_control/CMakeLists.txt b/kuka_driver_examples/robot_control/CMakeLists.txt index b89fbb84..9134de9b 100644 --- a/kuka_driver_examples/robot_control/CMakeLists.txt +++ b/kuka_driver_examples/robot_control/CMakeLists.txt @@ -20,7 +20,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(sensor_msgs REQUIRED) -find_package(kuka_sunrise_interfaces REQUIRED) +find_package(kuka_driver_interfaces REQUIRED) find_package(kroshu_ros2_core REQUIRED) include_directories(include ${kroshu_ros2_core_INCLUDE_DIRS}) @@ -28,23 +28,23 @@ include_directories(include ${kroshu_ros2_core_INCLUDE_DIRS}) add_library(joint_controller_base include/robot_control/joint_controller_base.hpp src/robot_control/joint_controller_base.cpp) -ament_target_dependencies(joint_controller_base rclcpp sensor_msgs kuka_sunrise_interfaces kroshu_ros2_core) +ament_target_dependencies(joint_controller_base rclcpp sensor_msgs kuka_driver_interfaces kroshu_ros2_core) target_link_libraries(joint_controller_base ${kroshu_ros2_core_LIBRARIES}) add_library(interpolating_controller_lib include/robot_control/interpolating_controller.hpp src/robot_control/interpolating_controller.cpp) -ament_target_dependencies(interpolating_controller_lib rclcpp sensor_msgs kuka_sunrise_interfaces) +ament_target_dependencies(interpolating_controller_lib rclcpp sensor_msgs kuka_driver_interfaces) target_link_libraries(interpolating_controller_lib joint_controller_base) add_executable(interpolating_controller src/robot_control/interpolating_controller_executable.cpp) -ament_target_dependencies(interpolating_controller rclcpp sensor_msgs kuka_sunrise_interfaces) +ament_target_dependencies(interpolating_controller rclcpp sensor_msgs kuka_driver_interfaces) target_link_libraries(interpolating_controller interpolating_controller_lib) add_executable(rate_scaled_controller src/robot_control/rate_scaled_controller.cpp) -ament_target_dependencies(rate_scaled_controller rclcpp sensor_msgs kuka_sunrise_interfaces) +ament_target_dependencies(rate_scaled_controller rclcpp sensor_msgs kuka_driver_interfaces) target_link_libraries(rate_scaled_controller interpolating_controller_lib) install(TARGETS interpolating_controller diff --git a/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp b/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp index d7d3cf9a..adb8bd3d 100644 --- a/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp +++ b/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp @@ -23,8 +23,8 @@ #include "lifecycle_msgs/msg/state.hpp" #include "sensor_msgs/msg/joint_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "kuka_sunrise_interfaces/srv/set_double.hpp" -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "kuka_driver_interfaces/srv/set_double.hpp" +#include "kuka_driver_interfaces/srv/set_int.hpp" #include "robot_control/joint_controller_base.hpp" diff --git a/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp b/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp index 257f340a..bbb33bf3 100644 --- a/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp +++ b/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp @@ -22,8 +22,8 @@ #include "lifecycle_msgs/msg/state.hpp" #include "sensor_msgs/msg/joint_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "kuka_sunrise_interfaces/srv/set_double.hpp" -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "kuka_driver_interfaces/srv/set_double.hpp" +#include "kuka_driver_interfaces/srv/set_int.hpp" #include "kroshu_ros2_core/ROS2BaseLCNode.hpp" @@ -72,8 +72,8 @@ class JointControllerBase : public kroshu_ros2_core::ROS2BaseLCNode rclcpp_lifecycle::LifecyclePublisher::SharedPtr joint_command_publisher_; rclcpp::Subscription::SharedPtr measured_joint_state_listener_; - rclcpp::Service::SharedPtr sync_send_period_service_; - rclcpp::Service::SharedPtr sync_receive_multiplier_service_; + rclcpp::Service::SharedPtr sync_send_period_service_; + rclcpp::Service::SharedPtr sync_receive_multiplier_service_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr joint_controller_is_active_publisher_; diff --git a/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp b/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp index cc9b5d6a..65953d27 100644 --- a/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp +++ b/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp @@ -23,8 +23,8 @@ #include "lifecycle_msgs/msg/state.hpp" #include "sensor_msgs/msg/joint_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "kuka_sunrise_interfaces/srv/set_double.hpp" -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "kuka_driver_interfaces/srv/set_double.hpp" +#include "kuka_driver_interfaces/srv/set_int.hpp" #include "robot_control/interpolating_controller.hpp" @@ -46,7 +46,7 @@ class RateScaledJointController : public InterpolatingController void setSlowStart(); bool OnReferenceRateChangeRequest(const double & reference_rate); - rclcpp::Service::SharedPtr set_rate_service_; + rclcpp::Service::SharedPtr set_rate_service_; std::vector prev_ref_joint_pos_ = std::vector(n_dof_); std::vector pprev_ref_joint_pos_ = std::vector(n_dof_); diff --git a/kuka_driver_examples/robot_control/package.xml b/kuka_driver_examples/robot_control/package.xml index 4357d021..9f7028db 100644 --- a/kuka_driver_examples/robot_control/package.xml +++ b/kuka_driver_examples/robot_control/package.xml @@ -12,7 +12,7 @@ rclcpp sensor_msgs rclcpp_lifecycle - kuka_sunrise_interfaces + kuka_driver_interfaces kroshu_ros2_core rclcpp diff --git a/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp b/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp index 3ae8fea9..46465690 100644 --- a/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp +++ b/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp @@ -107,8 +107,8 @@ JointControllerBase::JointControllerBase( }); auto send_period_callback = [this]( - kuka_sunrise_interfaces::srv::SetInt::Request::SharedPtr request, - kuka_sunrise_interfaces::srv::SetInt::Response::SharedPtr response) { + kuka_driver_interfaces::srv::SetInt::Request::SharedPtr request, + kuka_driver_interfaces::srv::SetInt::Response::SharedPtr response) { if (this->get_current_state().label() != "active") { send_period_ms_ = request->data; loop_period_ms_ = send_period_ms_ * receive_multiplier_; @@ -126,11 +126,11 @@ JointControllerBase::JointControllerBase( }; sync_send_period_service_ = this->create_service< - kuka_sunrise_interfaces::srv::SetInt>("sync_send_period", send_period_callback); + kuka_driver_interfaces::srv::SetInt>("sync_send_period", send_period_callback); auto receive_multiplier_callback = [this]( - kuka_sunrise_interfaces::srv::SetInt::Request::SharedPtr request, - kuka_sunrise_interfaces::srv::SetInt::Response::SharedPtr response) { + kuka_driver_interfaces::srv::SetInt::Request::SharedPtr request, + kuka_driver_interfaces::srv::SetInt::Response::SharedPtr response) { if (this->get_current_state().label() != "active") { receive_multiplier_ = request->data; loop_period_ms_ = send_period_ms_ * receive_multiplier_; @@ -148,7 +148,7 @@ JointControllerBase::JointControllerBase( }; sync_receive_multiplier_service_ = this->create_service< - kuka_sunrise_interfaces::srv::SetInt>("sync_receive_multiplier", receive_multiplier_callback); + kuka_driver_interfaces::srv::SetInt>("sync_receive_multiplier", receive_multiplier_callback); } rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn JointControllerBase:: diff --git a/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt b/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt index da658bf2..f04fdcde 100644 --- a/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt +++ b/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt @@ -24,7 +24,7 @@ find_package(geometry_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(std_srvs REQUIRED) find_package(kuka_sunrise REQUIRED) -find_package(kuka_sunrise_interfaces REQUIRED) +find_package(kuka_driver_interfaces REQUIRED) find_package(kroshu_ros2_core REQUIRED) include_directories(include) @@ -35,7 +35,7 @@ ament_target_dependencies(keyboard_control rclcpp rclcpp_lifecycle sensor_msgs g add_executable(system_manager src/control_system/system_manager.cpp) -ament_target_dependencies(system_manager rclcpp rclcpp_lifecycle std_msgs std_srvs kuka_sunrise_interfaces kroshu_ros2_core sensor_msgs) +ament_target_dependencies(system_manager rclcpp rclcpp_lifecycle std_msgs std_srvs kuka_driver_interfaces kroshu_ros2_core sensor_msgs) target_link_libraries(system_manager kuka_sunrise::internal) install(TARGETS keyboard_control system_manager diff --git a/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp b/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp index 826fda0b..3c57cdc7 100644 --- a/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp +++ b/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp @@ -27,7 +27,7 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" #include "sensor_msgs/msg/joint_state.hpp" -#include "kuka_sunrise_interfaces/srv/get_state.hpp" +#include "kuka_driver_interfaces/srv/get_state.hpp" #include "kuka_sunrise/internal/service_tools.hpp" #include "kroshu_ros2_core/ROS2BaseLCNode.hpp" @@ -74,7 +74,7 @@ class SystemManager : public kroshu_ros2_core::ROS2BaseLCNode rclcpp::Subscription::SharedPtr robot_commanding_state_subscription_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr manage_processing_publisher_; rclcpp::Client::SharedPtr change_robot_commanding_state_client_; - rclcpp::Client::SharedPtr get_state_client_; + rclcpp::Client::SharedPtr get_state_client_; rclcpp::Service::SharedPtr trigger_change_service_; rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp::QoS qos_ = rclcpp::QoS(rclcpp::KeepLast(10)); diff --git a/kuka_driver_examples/teleop_guided_robot/package.xml b/kuka_driver_examples/teleop_guided_robot/package.xml index 48c0f2d8..179ce082 100644 --- a/kuka_driver_examples/teleop_guided_robot/package.xml +++ b/kuka_driver_examples/teleop_guided_robot/package.xml @@ -15,7 +15,7 @@ geometry_msgs std_msgs std_srvs - kuka_sunrise_interfaces + kuka_driver_interfaces kuka_sunrise kroshu_ros2_core diff --git a/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp b/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp index 46fcb31a..beba4fa3 100644 --- a/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp +++ b/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp @@ -42,7 +42,7 @@ SystemManager::SystemManager( }); get_state_client_ = - this->create_client( + this->create_client( "robot_control/get_fri_state"); manage_processing_publisher_ = this->create_publisher( "system_manager/manage", 1); @@ -311,11 +311,11 @@ void SystemManager::getFRIState() RCLCPP_INFO(this->get_logger(), "service not available, waiting again..."); } auto request = std::make_shared< - kuka_sunrise_interfaces::srv::GetState::Request>(); + kuka_driver_interfaces::srv::GetState::Request>(); auto response_received_callback = [this]( - rclcpp::Client::SharedFuture future) { + rclcpp::Client::SharedFuture future) { auto result = future.get(); lbr_state_ = static_cast(result->data); diff --git a/kuka_sunrise_interfaces/CMakeLists.txt b/kuka_driver_interfaces/CMakeLists.txt similarity index 95% rename from kuka_sunrise_interfaces/CMakeLists.txt rename to kuka_driver_interfaces/CMakeLists.txt index a4dc3ebe..5aeb3a34 100644 --- a/kuka_sunrise_interfaces/CMakeLists.txt +++ b/kuka_driver_interfaces/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(kuka_sunrise_interfaces) +project(kuka_driver_interfaces) # Default to C99 if(NOT CMAKE_C_STANDARD) diff --git a/kuka_sunrise_interfaces/msg/RobotState.msg b/kuka_driver_interfaces/msg/RobotState.msg similarity index 100% rename from kuka_sunrise_interfaces/msg/RobotState.msg rename to kuka_driver_interfaces/msg/RobotState.msg diff --git a/kuka_sunrise_interfaces/package.xml b/kuka_driver_interfaces/package.xml similarity index 95% rename from kuka_sunrise_interfaces/package.xml rename to kuka_driver_interfaces/package.xml index 20a38525..922f71e5 100644 --- a/kuka_sunrise_interfaces/package.xml +++ b/kuka_driver_interfaces/package.xml @@ -1,7 +1,7 @@ - kuka_sunrise_interfaces + kuka_driver_interfaces 0.0.0 TODO: Package description rosdeveloper diff --git a/kuka_sunrise_interfaces/srv/GetState.srv b/kuka_driver_interfaces/srv/GetState.srv similarity index 100% rename from kuka_sunrise_interfaces/srv/GetState.srv rename to kuka_driver_interfaces/srv/GetState.srv diff --git a/kuka_sunrise_interfaces/srv/SetDouble.srv b/kuka_driver_interfaces/srv/SetDouble.srv similarity index 100% rename from kuka_sunrise_interfaces/srv/SetDouble.srv rename to kuka_driver_interfaces/srv/SetDouble.srv diff --git a/kuka_sunrise_interfaces/srv/SetInt.srv b/kuka_driver_interfaces/srv/SetInt.srv similarity index 100% rename from kuka_sunrise_interfaces/srv/SetInt.srv rename to kuka_driver_interfaces/srv/SetInt.srv diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index d345b502..e63f0a1d 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -23,7 +23,7 @@ find_package(rclcpp_lifecycle REQUIRED) find_package(std_msgs REQUIRED) find_package(std_srvs REQUIRED) find_package(sensor_msgs REQUIRED) -find_package(kuka_sunrise_interfaces REQUIRED) +find_package(kuka_driver_interfaces REQUIRED) find_package(kroshu_ros2_core REQUIRED) find_package(fri REQUIRED) find_package(hardware_interface REQUIRED) @@ -51,25 +51,25 @@ add_library(robot_manager SHARED add_library(kuka_fri_hw_interface SHARED src/kuka_sunrise/kuka_fri_hardware_interface.cpp ) -ament_target_dependencies(kuka_fri_hw_interface kuka_sunrise_interfaces rclcpp rclcpp_lifecycle hardware_interface) +ament_target_dependencies(kuka_fri_hw_interface kuka_driver_interfaces rclcpp rclcpp_lifecycle hardware_interface) target_link_libraries(kuka_fri_hw_interface fri::fri_client) add_library(configuration_manager SHARED src/kuka_sunrise/configuration_manager.cpp) -ament_target_dependencies(configuration_manager kuka_sunrise_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core +ament_target_dependencies(configuration_manager kuka_driver_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core controller_manager_msgs) add_executable(robot_manager_node src/kuka_sunrise/robot_manager_node.cpp) -ament_target_dependencies(robot_manager_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle kroshu_ros2_core controller_manager_msgs) +ament_target_dependencies(robot_manager_node kuka_driver_interfaces rclcpp rclcpp_lifecycle kroshu_ros2_core controller_manager_msgs) target_link_libraries(robot_manager_node robot_manager configuration_manager) add_executable(sunrise_control_node src/kuka_sunrise/sunrise_control_node.cpp) -ament_target_dependencies(sunrise_control_node kuka_sunrise_interfaces rclcpp rclcpp_lifecycle controller_manager) +ament_target_dependencies(sunrise_control_node kuka_driver_interfaces rclcpp rclcpp_lifecycle controller_manager) add_executable(position_controller_node test/position_controller.cpp) diff --git a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp index 7a10e12d..c543cc15 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/configuration_manager.hpp @@ -25,7 +25,7 @@ #include "lifecycle_msgs/msg/state.hpp" #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "kuka_driver_interfaces/srv/set_int.hpp" #include "controller_manager_msgs/srv/list_controllers.hpp" #include "kroshu_ros2_core/ROS2BaseLCNode.hpp" @@ -50,7 +50,7 @@ class ConfigurationManager std::shared_ptr robot_manager_; rclcpp::CallbackGroup::SharedPtr cbg_; rclcpp::CallbackGroup::SharedPtr param_cbg_; - rclcpp::Client::SharedPtr receive_multiplier_client_; + rclcpp::Client::SharedPtr receive_multiplier_client_; rclcpp::Client::SharedPtr get_controllers_client_; rclcpp::Service::SharedPtr set_parameter_service_; diff --git a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp index c56cc3a1..5a4793bd 100644 --- a/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp +++ b/kuka_sunrise_driver/include/kuka_sunrise/kuka_fri_hardware_interface.hpp @@ -26,7 +26,7 @@ #include #include -#include "kuka_sunrise_interfaces/srv/set_int.hpp" +#include "kuka_driver_interfaces/srv/set_int.hpp" #include "kuka_sunrise/internal/activatable_interface.hpp" #include "fri/friLBRClient.h" #include "fri/HWIFClientApplication.hpp" @@ -92,7 +92,7 @@ class KUKAFRIHardwareInterface : public hardware_interface::SystemInterface, KUKA::FRI::HWIFClientApplication client_application_; KUKA::FRI::UdpConnection udp_connection_; - rclcpp::Service::SharedPtr set_receive_multiplier_service_; + rclcpp::Service::SharedPtr set_receive_multiplier_service_; rclcpp::Clock ros_clock_; // Command interface must be of type double, but controller can set only integers diff --git a/kuka_sunrise_driver/package.xml b/kuka_sunrise_driver/package.xml index 2929acce..ea736d45 100644 --- a/kuka_sunrise_driver/package.xml +++ b/kuka_sunrise_driver/package.xml @@ -18,7 +18,7 @@ std_msgs std_srvs sensor_msgs - kuka_sunrise_interfaces + kuka_driver_interfaces kroshu_ros2_core hardware_interface controller_manager diff --git a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp index 0bce9ac3..c5bcca8a 100644 --- a/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp +++ b/kuka_sunrise_driver/src/kuka_sunrise/configuration_manager.cpp @@ -34,7 +34,7 @@ ConfigurationManager::ConfigurationManager( param_cbg_ = robot_manager_node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); receive_multiplier_client_ = robot_manager_node->create_client< - kuka_sunrise_interfaces::srv::SetInt>( + kuka_driver_interfaces::srv::SetInt>( "set_receive_multiplier", qos.get_rmw_qos_profile(), cbg_); @@ -262,9 +262,9 @@ bool ConfigurationManager::setCommandMode(const std::string & command_mode) cons bool ConfigurationManager::setReceiveMultiplier(int receive_multiplier) const { // Set receive multiplier of hardware interface through controller manager service - auto request = std::make_shared(); + auto request = std::make_shared(); request->data = receive_multiplier; - auto response = kuka_sunrise::sendRequest( + auto response = kuka_sunrise::sendRequest( receive_multiplier_client_, request, 0, 1000); if (!response || !response->success) { From 35295b48c3a8e378555cf7fd0ef29fa3b6c5472f Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 12:32:29 +0100 Subject: [PATCH 90/94] remove demo packages for old driver --- .../robot_control/CMakeLists.txt | 65 --- .../robot_control/config/kr6.yaml | 7 - .../robot_control/config/lbr_iiwa.yaml | 7 - .../interpolating_controller.hpp | 58 --- .../robot_control/joint_controller_base.hpp | 96 ----- .../robot_control/rate_scaled_controller.hpp | 63 --- .../robot_control/package.xml | 28 -- .../interpolating_controller.cpp | 122 ------ .../interpolating_controller_executable.cpp | 31 -- .../robot_control/joint_controller_base.cpp | 278 ------------- .../robot_control/rate_scaled_controller.cpp | 194 --------- .../teleop_guided_robot/CMakeLists.txt | 58 --- .../control_logic/keyboard_control.hpp | 75 ---- .../include/control_system/system_manager.hpp | 89 ---- .../launch/keyboard_guided_robot.launch.py | 56 --- .../launch/kss_control.launch.py | 64 --- .../launch/sunrise_control.launch.py | 78 ---- .../teleop_guided_robot/package.xml | 32 -- .../src/control_logic/keyboard_control.cpp | 184 --------- .../src/control_system/system_manager.cpp | 380 ------------------ sonar-project.properties | 2 +- 21 files changed, 1 insertion(+), 1966 deletions(-) delete mode 100644 kuka_driver_examples/robot_control/CMakeLists.txt delete mode 100644 kuka_driver_examples/robot_control/config/kr6.yaml delete mode 100644 kuka_driver_examples/robot_control/config/lbr_iiwa.yaml delete mode 100644 kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp delete mode 100644 kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp delete mode 100644 kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp delete mode 100644 kuka_driver_examples/robot_control/package.xml delete mode 100644 kuka_driver_examples/robot_control/src/robot_control/interpolating_controller.cpp delete mode 100644 kuka_driver_examples/robot_control/src/robot_control/interpolating_controller_executable.cpp delete mode 100644 kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp delete mode 100644 kuka_driver_examples/robot_control/src/robot_control/rate_scaled_controller.cpp delete mode 100644 kuka_driver_examples/teleop_guided_robot/CMakeLists.txt delete mode 100644 kuka_driver_examples/teleop_guided_robot/include/control_logic/keyboard_control.hpp delete mode 100644 kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp delete mode 100644 kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py delete mode 100644 kuka_driver_examples/teleop_guided_robot/launch/kss_control.launch.py delete mode 100644 kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py delete mode 100644 kuka_driver_examples/teleop_guided_robot/package.xml delete mode 100644 kuka_driver_examples/teleop_guided_robot/src/control_logic/keyboard_control.cpp delete mode 100644 kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp diff --git a/kuka_driver_examples/robot_control/CMakeLists.txt b/kuka_driver_examples/robot_control/CMakeLists.txt deleted file mode 100644 index 9134de9b..00000000 --- a/kuka_driver_examples/robot_control/CMakeLists.txt +++ /dev/null @@ -1,65 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(robot_control) - -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_lifecycle REQUIRED) -find_package(sensor_msgs REQUIRED) -find_package(kuka_driver_interfaces REQUIRED) -find_package(kroshu_ros2_core REQUIRED) - -include_directories(include ${kroshu_ros2_core_INCLUDE_DIRS}) - -add_library(joint_controller_base - include/robot_control/joint_controller_base.hpp - src/robot_control/joint_controller_base.cpp) -ament_target_dependencies(joint_controller_base rclcpp sensor_msgs kuka_driver_interfaces kroshu_ros2_core) -target_link_libraries(joint_controller_base ${kroshu_ros2_core_LIBRARIES}) - -add_library(interpolating_controller_lib - include/robot_control/interpolating_controller.hpp - src/robot_control/interpolating_controller.cpp) -ament_target_dependencies(interpolating_controller_lib rclcpp sensor_msgs kuka_driver_interfaces) -target_link_libraries(interpolating_controller_lib joint_controller_base) - -add_executable(interpolating_controller - src/robot_control/interpolating_controller_executable.cpp) -ament_target_dependencies(interpolating_controller rclcpp sensor_msgs kuka_driver_interfaces) -target_link_libraries(interpolating_controller interpolating_controller_lib) - -add_executable(rate_scaled_controller - src/robot_control/rate_scaled_controller.cpp) -ament_target_dependencies(rate_scaled_controller rclcpp sensor_msgs kuka_driver_interfaces) -target_link_libraries(rate_scaled_controller interpolating_controller_lib) - -install(TARGETS interpolating_controller - DESTINATION lib/${PROJECT_NAME}) - -install(TARGETS rate_scaled_controller - DESTINATION lib/${PROJECT_NAME}) - -install(DIRECTORY config - DESTINATION share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/kuka_driver_examples/robot_control/config/kr6.yaml b/kuka_driver_examples/robot_control/config/kr6.yaml deleted file mode 100644 index 38970d0d..00000000 --- a/kuka_driver_examples/robot_control/config/kr6.yaml +++ /dev/null @@ -1,7 +0,0 @@ -joint_controller: - ros__parameters: - n_dof: 6 - velocity_limits_deg: [360.0, 300.0, 360.0, 381.0, 388.0, 615.0] - lower_limits_deg: [-170.0, -190.0, -120.0, -185.0, -120.0, -350.0] - upper_limits_deg: [170.0, 45.0, 156.0, 185.0, 120.0, 350.0] - diff --git a/kuka_driver_examples/robot_control/config/lbr_iiwa.yaml b/kuka_driver_examples/robot_control/config/lbr_iiwa.yaml deleted file mode 100644 index f5bb9962..00000000 --- a/kuka_driver_examples/robot_control/config/lbr_iiwa.yaml +++ /dev/null @@ -1,7 +0,0 @@ -joint_controller: - ros__parameters: - n_dof: 7 - velocity_limits_deg: [300.0, 300.0, 400.0, 300.0, 160.0, 160.0, 400.0] - lower_limits_deg: [-170.0, -120.0, -170.0, -120.0, -170.0, -120.0, -175.0] - upper_limits_deg: [170.0, 120.0, 170.0, 120.0, 170.0, 120.0, 175.0] - diff --git a/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp b/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp deleted file mode 100644 index adb8bd3d..00000000 --- a/kuka_driver_examples/robot_control/include/robot_control/interpolating_controller.hpp +++ /dev/null @@ -1,58 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef ROBOT_CONTROL__INTERPOLATING_CONTROLLER_HPP_ -#define ROBOT_CONTROL__INTERPOLATING_CONTROLLER_HPP_ - -#include -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "lifecycle_msgs/msg/state.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "kuka_driver_interfaces/srv/set_double.hpp" -#include "kuka_driver_interfaces/srv/set_int.hpp" - -#include "robot_control/joint_controller_base.hpp" - - -namespace robot_control -{ -class InterpolatingController : public JointControllerBase -{ -public: - InterpolatingController( - const std::string & node_name, - const rclcpp::NodeOptions & options); - ~InterpolatingController() override = default; - -protected: - void controlLoopCallback(sensor_msgs::msg::JointState::SharedPtr measured_joint_state) override; - void referenceUpdateCallback( - sensor_msgs::msg::JointState::SharedPtr reference_joint_state); - virtual void setJointCommandPosition(const std::vector &); - virtual void enforceSpeedLimits(const std::vector & measured_joint_position); - sensor_msgs::msg::JointState::ConstSharedPtr refJointState() const; - -private: - rclcpp::Subscription::SharedPtr reference_joint_state_listener_; - rclcpp::CallbackGroup::SharedPtr cbg_; - sensor_msgs::msg::JointState::SharedPtr reference_joint_state_; -}; -} // namespace robot_control - - -#endif // ROBOT_CONTROL__INTERPOLATING_CONTROLLER_HPP_ diff --git a/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp b/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp deleted file mode 100644 index bbb33bf3..00000000 --- a/kuka_driver_examples/robot_control/include/robot_control/joint_controller_base.hpp +++ /dev/null @@ -1,96 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef ROBOT_CONTROL__JOINT_CONTROLLER_BASE_HPP_ -#define ROBOT_CONTROL__JOINT_CONTROLLER_BASE_HPP_ - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "lifecycle_msgs/msg/state.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "kuka_driver_interfaces/srv/set_double.hpp" -#include "kuka_driver_interfaces/srv/set_int.hpp" - -#include "kroshu_ros2_core/ROS2BaseLCNode.hpp" - -namespace robot_control -{ -class JointControllerBase : public kroshu_ros2_core::ROS2BaseLCNode -{ -public: - JointControllerBase( - const std::string & node_name, - const rclcpp::NodeOptions & options); - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_configure(const rclcpp_lifecycle::State &) override; - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_cleanup(const rclcpp_lifecycle::State &) override; - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_activate(const rclcpp_lifecycle::State &) override; - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_deactivate(const rclcpp_lifecycle::State &) override; - -protected: - uint8_t n_dof_ = 7; - void jointStateMeasurementsCallback(sensor_msgs::msg::JointState::SharedPtr measured_joint_state); - virtual void controlLoopCallback( - sensor_msgs::msg::JointState::SharedPtr measured_joint_state) = 0; - void updateMaxPositionDifference(); - bool onVelocityFactorsChangeRequest(const std::vector & vel_factor); - - const std::vector & maxPosDiff() const; - const std::vector & lowerLimitsRad() const; - const std::vector & upperLimitsRad() const; - const int & loopPeriod() const; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - jointCommandPublisher() - const; - - sensor_msgs::msg::JointState joint_command_; - - static constexpr int ms_in_sec_ = 1000; - -private: - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - joint_command_publisher_; - rclcpp::Subscription::SharedPtr measured_joint_state_listener_; - rclcpp::Service::SharedPtr sync_send_period_service_; - rclcpp::Service::SharedPtr sync_receive_multiplier_service_; - - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - joint_controller_is_active_publisher_; - std_msgs::msg::Bool joint_controller_is_active_; - - std::vector max_velocities_radPs_ = std::vector(n_dof_); - std::vector velocity_limits_radPs_ = std::vector(n_dof_); - std::vector lower_limits_rad_ = std::vector(n_dof_); - std::vector upper_limits_rad_ = std::vector(n_dof_); - std::vector max_position_difference_ = std::vector(n_dof_); - - int send_period_ms_ = 10; - int receive_multiplier_ = 1; - int loop_count_ = 0; - int loop_period_ms_ = 10; -}; -} // namespace robot_control - - -#endif // ROBOT_CONTROL__JOINT_CONTROLLER_BASE_HPP_ diff --git a/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp b/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp deleted file mode 100644 index 65953d27..00000000 --- a/kuka_driver_examples/robot_control/include/robot_control/rate_scaled_controller.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef ROBOT_CONTROL__RATE_SCALED_CONTROLLER_HPP_ -#define ROBOT_CONTROL__RATE_SCALED_CONTROLLER_HPP_ - -#include -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "lifecycle_msgs/msg/state.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "kuka_driver_interfaces/srv/set_double.hpp" -#include "kuka_driver_interfaces/srv/set_int.hpp" - -#include "robot_control/interpolating_controller.hpp" - - -namespace robot_control -{ - -class RateScaledJointController : public InterpolatingController -{ -public: - RateScaledJointController( - const std::string & node_name, - const rclcpp::NodeOptions & options); - ~RateScaledJointController() override = default; - -private: - void setJointCommandPosition(const std::vector & measured_joint_position) final; - void enforceSpeedLimits(const std::vector & measured_joint_position) final; - void setSlowStart(); - bool OnReferenceRateChangeRequest(const double & reference_rate); - - rclcpp::Service::SharedPtr set_rate_service_; - - std::vector prev_ref_joint_pos_ = std::vector(n_dof_); - std::vector pprev_ref_joint_pos_ = std::vector(n_dof_); - std::vector slow_start_ = std::vector(n_dof_, true); - - int cmd_count_ = 0; - int cmd_per_frame_temp_ = 0; // for syncing changing with commands - int cmd_per_frame_; - bool start_flag_ = true; -}; -} // namespace robot_control - - -#endif // ROBOT_CONTROL__RATE_SCALED_CONTROLLER_HPP_ diff --git a/kuka_driver_examples/robot_control/package.xml b/kuka_driver_examples/robot_control/package.xml deleted file mode 100644 index 9f7028db..00000000 --- a/kuka_driver_examples/robot_control/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - robot_control - 0.0.0 - Controller for kroshu robots - Gergely Kovacs - Apache 2.0 - - ament_cmake - - rclcpp - sensor_msgs - rclcpp_lifecycle - kuka_driver_interfaces - kroshu_ros2_core - - rclcpp - sensor_msgs - rclcpp_lifecycle - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/kuka_driver_examples/robot_control/src/robot_control/interpolating_controller.cpp b/kuka_driver_examples/robot_control/src/robot_control/interpolating_controller.cpp deleted file mode 100644 index bd988491..00000000 --- a/kuka_driver_examples/robot_control/src/robot_control/interpolating_controller.cpp +++ /dev/null @@ -1,122 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "robot_control/interpolating_controller.hpp" - -#include -#include -#include -#include - -namespace robot_control -{ -InterpolatingController::InterpolatingController( - const std::string & node_name, - const rclcpp::NodeOptions & options) -: JointControllerBase(node_name, options) -{ - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - - reference_joint_state_listener_ = this->create_subscription< - sensor_msgs::msg::JointState>( - "reference_joint_state", qos, - [this](sensor_msgs::msg::JointState::SharedPtr state) { - this->referenceUpdateCallback(state); - }); -} - -void InterpolatingController::controlLoopCallback( - sensor_msgs::msg::JointState::SharedPtr measured_joint_state) -{ - if (!reference_joint_state_) { - reference_joint_state_ = measured_joint_state; - } - if (reference_joint_state_->position.size() == n_dof_) { - setJointCommandPosition(measured_joint_state->position); - enforceSpeedLimits(measured_joint_state->position); - } - if (reference_joint_state_->velocity.size() == n_dof_) { - joint_command_.velocity = reference_joint_state_->velocity; - } - if (reference_joint_state_->effort.size() == n_dof_) { - joint_command_.effort = reference_joint_state_->effort; - } - joint_command_.header = measured_joint_state->header; - jointCommandPublisher()->publish(joint_command_); -} - - -void InterpolatingController::setJointCommandPosition( - const std::vector &) -{ - joint_command_.position = reference_joint_state_->position; -} - -void InterpolatingController::enforceSpeedLimits( - const std::vector & measured_joint_position) -{ - std::vector & joint_command_position = joint_command_.position; - for (int i = 0; i < n_dof_; i++) { - if (abs(measured_joint_position[i] - joint_command_position[i]) <= - maxPosDiff()[i]) - { - RCLCPP_DEBUG( - get_logger(), - "Successfully set step size to the speed of movement"); - } else if (joint_command_position[i] > measured_joint_position[i]) { - joint_command_position[i] = measured_joint_position[i] + - maxPosDiff()[i]; - RCLCPP_DEBUG(get_logger(), "Movement was too fast around joint %i", i + 1); - - } else if (joint_command_position[i] < measured_joint_position[i]) { - joint_command_position[i] = measured_joint_position[i] - - maxPosDiff()[i]; - RCLCPP_DEBUG(get_logger(), "Movement was too fast around joint %i", i + 1); - - } else { - RCLCPP_ERROR(get_logger(), "Reference or measured joint state is NaN"); - } - } -} - -void InterpolatingController::referenceUpdateCallback( - sensor_msgs::msg::JointState::SharedPtr reference_joint_state) -{ - if (this->get_current_state().label() != "active") { - return; - } - auto & reference_joint_positions = reference_joint_state->position; - for (int i = 0; i < n_dof_; i++) { - if (reference_joint_positions[i] < lowerLimitsRad()[i]) { - reference_joint_positions[i] = lowerLimitsRad()[i]; - RCLCPP_WARN( - get_logger(), - "Reference for joint %i exceeded lower limit", i + 1); - } else if (reference_joint_positions[i] > upperLimitsRad()[i]) { - reference_joint_positions[i] = upperLimitsRad()[i]; - RCLCPP_WARN( - get_logger(), - "Reference for joint %i exceeded upper limit", i + 1); - } - } - reference_joint_state_ = reference_joint_state; -} - -sensor_msgs::msg::JointState::ConstSharedPtr InterpolatingController::refJointState() const -{ - return reference_joint_state_; -} - -} // namespace robot_control diff --git a/kuka_driver_examples/robot_control/src/robot_control/interpolating_controller_executable.cpp b/kuka_driver_examples/robot_control/src/robot_control/interpolating_controller_executable.cpp deleted file mode 100644 index efd927cb..00000000 --- a/kuka_driver_examples/robot_control/src/robot_control/interpolating_controller_executable.cpp +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include "robot_control/interpolating_controller.hpp" - -int main(int argc, char * argv[]) -{ - setvbuf(stdout, nullptr, _IONBF, BUFSIZ); - - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared( - "joint_controller", rclcpp::NodeOptions()); - executor.add_node(node->get_node_base_interface()); - executor.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp b/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp deleted file mode 100644 index 46465690..00000000 --- a/kuka_driver_examples/robot_control/src/robot_control/joint_controller_base.cpp +++ /dev/null @@ -1,278 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "robot_control/joint_controller_base.hpp" - -#include -#include -#include -#include - -namespace robot_control -{ -double d2r(double degrees) -{ - return degrees / 180 * M_PI; -} - -JointControllerBase::JointControllerBase( - const std::string & node_name, - const rclcpp::NodeOptions & options) -: kroshu_ros2_core::ROS2BaseLCNode(node_name, options) -{ - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - - measured_joint_state_listener_ = this->create_subscription< - sensor_msgs::msg::JointState>( - "measured_joint_state", qos, - [this](sensor_msgs::msg::JointState::SharedPtr state) { - this->jointStateMeasurementsCallback(state); - }); - - joint_command_publisher_ = this->create_publisher< - sensor_msgs::msg::JointState>("joint_command", qos); - joint_controller_is_active_publisher_ = this->create_publisher< - std_msgs::msg::Bool>("joint_controller_is_active", qos); - - registerStaticParameter( - "n_dof", 0, kroshu_ros2_core::ParameterSetAccessRights {true, false, false, false}, - [this](const uint8_t & n_dof) { - if (n_dof == 0) { - RCLCPP_ERROR(get_logger(), "Invalid config file"); - return false; - } - n_dof_ = n_dof; - return true; - }); - - registerStaticParameter>( - "lower_limits_deg", - std::vector(), kroshu_ros2_core::ParameterSetAccessRights {true, false, false, false}, - [this](const std::vector & lower_lim) { - if (lower_lim.size() == 0) { - RCLCPP_ERROR(get_logger(), "Invalid config file"); - return false; - } - std::transform( - lower_lim.begin(), lower_lim.end(), lower_limits_rad_.begin(), [](double l) - {return d2r(l * 0.9);}); - return true; - }); - - registerStaticParameter>( - "upper_limits_deg", - std::vector(), kroshu_ros2_core::ParameterSetAccessRights {true, false, - false, false}, [this](const std::vector & upper_lim) { - if (upper_lim.size() == 0) { - RCLCPP_ERROR(get_logger(), "Invalid config file"); - return false; - } - std::transform( - upper_lim.begin(), upper_lim.end(), upper_limits_rad_.begin(), [](double l) - {return d2r(l * 0.9);}); - return true; - }); - - registerStaticParameter>( - "velocity_limits_deg", - std::vector(), kroshu_ros2_core::ParameterSetAccessRights {true, false, false, false}, - [this](const std::vector & max_vel) { - if (max_vel.size() == 0) { - RCLCPP_ERROR(get_logger(), "Invalid config file"); - return false; - } - std::transform( - max_vel.begin(), max_vel.end(), max_velocities_radPs_.begin(), [](double v) - {return d2r(v * 0.9);}); - return true; - }); - - registerParameter>( - "velocity_factors", std::vector(n_dof_, 1.0), - kroshu_ros2_core::ParameterSetAccessRights {true, true, false, false}, - [this](const std::vector & vel_factor) { - return this->onVelocityFactorsChangeRequest(vel_factor); - }); - - auto send_period_callback = [this]( - kuka_driver_interfaces::srv::SetInt::Request::SharedPtr request, - kuka_driver_interfaces::srv::SetInt::Response::SharedPtr response) { - if (this->get_current_state().label() != "active") { - send_period_ms_ = request->data; - loop_period_ms_ = send_period_ms_ * receive_multiplier_; - updateMaxPositionDifference(); - RCLCPP_INFO( - get_logger(), - "Succesfully synced send period"); - response->success = true; - } else { - RCLCPP_ERROR( - get_logger(), - "Joint controller is active, could not change send_period"); - response->success = false; - } - }; - - sync_send_period_service_ = this->create_service< - kuka_driver_interfaces::srv::SetInt>("sync_send_period", send_period_callback); - - auto receive_multiplier_callback = [this]( - kuka_driver_interfaces::srv::SetInt::Request::SharedPtr request, - kuka_driver_interfaces::srv::SetInt::Response::SharedPtr response) { - if (this->get_current_state().label() != "active") { - receive_multiplier_ = request->data; - loop_period_ms_ = send_period_ms_ * receive_multiplier_; - updateMaxPositionDifference(); - RCLCPP_INFO( - get_logger(), - "Succesfully synced receive multiplier"); - response->success = true; - } else { - RCLCPP_ERROR( - get_logger(), - "Joint controller is active, could not change receive_multiplier"); - response->success = false; - } - }; - - sync_receive_multiplier_service_ = this->create_service< - kuka_driver_interfaces::srv::SetInt>("sync_receive_multiplier", receive_multiplier_callback); -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn JointControllerBase:: -on_configure( - const rclcpp_lifecycle::State &) -{ - joint_command_.position.resize(n_dof_); - joint_command_.velocity.resize(n_dof_); - joint_command_.effort.resize(n_dof_); - if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) { - RCLCPP_ERROR(get_logger(), "mlockall error"); - RCLCPP_ERROR(get_logger(), strerror(errno)); - return ERROR; - } - - struct sched_param param; - param.sched_priority = 90; - if (sched_setscheduler(0, SCHED_FIFO, ¶m) == -1) { - RCLCPP_ERROR(get_logger(), "setscheduler error"); - RCLCPP_ERROR(get_logger(), strerror(errno)); - return ERROR; - } - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn JointControllerBase:: -on_cleanup( - const rclcpp_lifecycle::State &) -{ - if (munlockall() == -1) { - RCLCPP_ERROR(get_logger(), "munlockall error"); - return ERROR; - } - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn JointControllerBase:: -on_activate( - const rclcpp_lifecycle::State &) -{ - joint_command_publisher_->on_activate(); - joint_controller_is_active_publisher_->on_activate(); - joint_controller_is_active_.data = true; - joint_controller_is_active_publisher_->publish(joint_controller_is_active_); - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn JointControllerBase:: -on_deactivate( - const rclcpp_lifecycle::State &) -{ - joint_command_publisher_->on_deactivate(); - joint_controller_is_active_.data = false; - joint_controller_is_active_publisher_->publish(joint_controller_is_active_); - joint_controller_is_active_publisher_->on_deactivate(); - return SUCCESS; -} - -bool JointControllerBase::onVelocityFactorsChangeRequest( - const std::vector & vel_factor) -{ - if (vel_factor.size() != n_dof_) { - RCLCPP_ERROR( - this->get_logger(), - "Invalid parameter array length for velocity factors "); - return false; - } - for (const auto & v : vel_factor) { - if (v > 1) { - RCLCPP_ERROR( - this->get_logger(), - "Factor should be <= 1"); - return false; - } - } - for (int i = 0; i < n_dof_; i++) { - velocity_limits_radPs_[i] = max_velocities_radPs_[i] * vel_factor[i]; - } - updateMaxPositionDifference(); - return true; -} - -void JointControllerBase::updateMaxPositionDifference() -{ - auto calc_pos_diff = [&loop_period_ms_ = loop_period_ms_](double v) { - return v * loop_period_ms_ / JointControllerBase::ms_in_sec_; - }; - std::transform( - velocity_limits_radPs_.begin(), velocity_limits_radPs_.end(), - max_position_difference_.begin(), calc_pos_diff); -} - -void JointControllerBase::jointStateMeasurementsCallback( - sensor_msgs::msg::JointState::SharedPtr measured_joint_state) -{ - if (++loop_count_ == receive_multiplier_) { - loop_count_ = 0; - controlLoopCallback(measured_joint_state); - } -} - -const std::vector & JointControllerBase::maxPosDiff() const -{ - return max_position_difference_; -} - -const std::vector & JointControllerBase::lowerLimitsRad() const -{ - return lower_limits_rad_; -} - -const std::vector & JointControllerBase::upperLimitsRad() const -{ - return upper_limits_rad_; -} - -const int & JointControllerBase::loopPeriod() const -{ - return loop_period_ms_; -} - -rclcpp_lifecycle::LifecyclePublisher::SharedPtr JointControllerBase:: -jointCommandPublisher() const -{ - return joint_command_publisher_; -} -} // namespace robot_control diff --git a/kuka_driver_examples/robot_control/src/robot_control/rate_scaled_controller.cpp b/kuka_driver_examples/robot_control/src/robot_control/rate_scaled_controller.cpp deleted file mode 100644 index de60c660..00000000 --- a/kuka_driver_examples/robot_control/src/robot_control/rate_scaled_controller.cpp +++ /dev/null @@ -1,194 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "robot_control/rate_scaled_controller.hpp" - -#include -#include -#include -#include - -namespace robot_control -{ - -RateScaledJointController::RateScaledJointController( - const std::string & node_name, - const rclcpp::NodeOptions & options) -: InterpolatingController(node_name, options) -{ - // Enforce setting parameter by giving invalid value as default - registerParameter( - "reference_rate", 0, kroshu_ros2_core::ParameterSetAccessRights {true, true, - false, false}, [this](const double & ref_rate) { - return this->OnReferenceRateChangeRequest(ref_rate); - }); -} - -void RateScaledJointController::setJointCommandPosition( - const std::vector & measured_joint_position) -{ - // referenceUpdateCallback is called is base class constructor, so it cannot be ovverriden - // as a workaround, set velocity scaling here, if reference has changed - if (refJointState()->position != prev_ref_joint_pos_) { - setSlowStart(); - } - const std::vector & reference_joint_position = - refJointState()->position; - std::vector & joint_command_position = joint_command_.position; - for (int i = 0; i < n_dof_; i++) { - if (maxPosDiff()[i] < 0) { - RCLCPP_WARN(get_logger(), "max position difference is not positive"); - } - double position_error = reference_joint_position[i] - - measured_joint_position[i]; - double reference_error = reference_joint_position[i] - - joint_command_position[i]; - - // Set speed so, that the motion finishes when the next reference is received - if (cmd_count_ >= cmd_per_frame_) { - joint_command_position[i] = reference_joint_position[i]; - if (i == 0) { - RCLCPP_DEBUG( - get_logger(), - "Frame not received in expected time, command count is %i", - cmd_count_); - } - } else if (start_flag_) { // First command: based on measured - joint_command_position[i] = measured_joint_position[i] + - position_error / (cmd_per_frame_ - cmd_count_); - if (i == 6) { - start_flag_ = false; - prev_ref_joint_pos_ = reference_joint_position; - } - RCLCPP_DEBUG(get_logger(), "First command"); - } else { // Not first command: based on previous command - joint_command_position[i] += reference_error / - (cmd_per_frame_ - cmd_count_); - RCLCPP_DEBUG(get_logger(), "Command calculated relative to previous"); - } - } -} - -void RateScaledJointController::enforceSpeedLimits( - const std::vector & measured_joint_position) -{ - std::vector & joint_command_position = joint_command_.position; - for (int i = 0; i < n_dof_; i++) { - // If axis is marked, slow down motion at new reference - double vel_factor; - if (slow_start_[i]) { - if (cmd_count_ == 0) { - vel_factor = 0.55; - } else if (cmd_count_ == 1) { - vel_factor = 0.8; - } else { - vel_factor = 1; - } - } else { - vel_factor = 1; - } - if (abs(measured_joint_position[i] - joint_command_position[i]) <= - maxPosDiff()[i] * vel_factor) - { - RCLCPP_DEBUG( - get_logger(), - "Successfully set step size to the speed of movement"); - } else if (joint_command_position[i] > measured_joint_position[i]) { - joint_command_position[i] = measured_joint_position[i] + - maxPosDiff()[i] * vel_factor; - RCLCPP_DEBUG(get_logger(), "Movement was too fast around joint %i", i + 1); - } else if (joint_command_position[i] < measured_joint_position[i]) { - joint_command_position[i] = measured_joint_position[i] - - maxPosDiff()[i] * vel_factor; - RCLCPP_DEBUG(get_logger(), "Movement was too fast around joint %i", i + 1); - } else { - RCLCPP_ERROR(get_logger(), "Reference or measured joint state is NaN"); - } - } - cmd_count_++; -} - -void RateScaledJointController::setSlowStart() -{ - auto & reference_joint_positions = refJointState()->position; - // if the change of reference changes sign, mark that axis to be slowed down - for (int i = 0; i < n_dof_; i++) { - if ((prev_ref_joint_pos_[i] - pprev_ref_joint_pos_[i]) * - (reference_joint_positions[i] - prev_ref_joint_pos_[i]) > 0) - { - slow_start_[i] = false; - } else if (reference_joint_positions[i] == prev_ref_joint_pos_[i]) { - slow_start_[i] = false; - } else if (reference_joint_positions[i] > prev_ref_joint_pos_[i] && // NOLINT - joint_command_.position[i] > reference_joint_positions[i]) - { - slow_start_[i] = false; - } else if (reference_joint_positions[i] < prev_ref_joint_pos_[i] && // NOLINT - joint_command_.position[i] < reference_joint_positions[i]) - { - slow_start_[i] = false; - } else { - slow_start_[i] = true; - } - } - RCLCPP_DEBUG(get_logger(), "commands per frame: %i", cmd_count_); - cmd_count_ = 0; - if (cmd_per_frame_temp_) { - cmd_per_frame_ = cmd_per_frame_temp_; - cmd_per_frame_temp_ = 0; - } - prev_ref_joint_pos_ = refJointState()->position; -} - -bool RateScaledJointController::OnReferenceRateChangeRequest(const double & reference_rate) -{ - if (reference_rate < 1) { - RCLCPP_ERROR( - get_logger(), - "Reference rate should be at least 1 [Hz]"); - return false; - } - int cmd_per_frame = static_cast(JointControllerBase::ms_in_sec_ / - loopPeriod() / reference_rate) + 1; - - if (cmd_per_frame < 2) { - RCLCPP_ERROR( - get_logger(), - "Control loop frequency should be bigger than command receive frequency"); - return false; - } - cmd_per_frame_temp_ = cmd_per_frame; - RCLCPP_INFO( - get_logger(), - "Successfully changed rate, receiving commands in every %i. frame", - cmd_per_frame); - return true; -} - - -} // namespace robot_control - -int main(int argc, char * argv[]) -{ - setvbuf(stdout, nullptr, _IONBF, BUFSIZ); - - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared( - "joint_controller", rclcpp::NodeOptions()); - executor.add_node(node->get_node_base_interface()); - executor.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt b/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt deleted file mode 100644 index f04fdcde..00000000 --- a/kuka_driver_examples/teleop_guided_robot/CMakeLists.txt +++ /dev/null @@ -1,58 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(teleop_guided_robot) - -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_lifecycle REQUIRED) -find_package(sensor_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(std_msgs REQUIRED) -find_package(std_srvs REQUIRED) -find_package(kuka_sunrise REQUIRED) -find_package(kuka_driver_interfaces REQUIRED) -find_package(kroshu_ros2_core REQUIRED) - -include_directories(include) - -add_executable(keyboard_control - src/control_logic/keyboard_control.cpp) -ament_target_dependencies(keyboard_control rclcpp rclcpp_lifecycle sensor_msgs geometry_msgs kroshu_ros2_core) - -add_executable(system_manager - src/control_system/system_manager.cpp) -ament_target_dependencies(system_manager rclcpp rclcpp_lifecycle std_msgs std_srvs kuka_driver_interfaces kroshu_ros2_core sensor_msgs) -target_link_libraries(system_manager kuka_sunrise::internal) - -install(TARGETS keyboard_control system_manager - DESTINATION lib/${PROJECT_NAME}) - -install(DIRECTORY launch - DESTINATION share/${PROJECT_NAME}) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # uncomment the line when a copyright and license is not present in all source files - #set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # uncomment the line when this package is not in a git repo - #set(ament_cmake_cpplint_FOUND TRUE) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/kuka_driver_examples/teleop_guided_robot/include/control_logic/keyboard_control.hpp b/kuka_driver_examples/teleop_guided_robot/include/control_logic/keyboard_control.hpp deleted file mode 100644 index db08f63a..00000000 --- a/kuka_driver_examples/teleop_guided_robot/include/control_logic/keyboard_control.hpp +++ /dev/null @@ -1,75 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CONTROL_LOGIC__KEYBOARD_CONTROL_HPP_ -#define CONTROL_LOGIC__KEYBOARD_CONTROL_HPP_ - -#include -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "lifecycle_msgs/msg/state.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "geometry_msgs/msg/twist.hpp" - -#include "kroshu_ros2_core/ROS2BaseLCNode.hpp" - -namespace teleop_guided_robot -{ -class KeyboardControl : public kroshu_ros2_core::ROS2BaseLCNode -{ -public: - KeyboardControl(const std::string & node_name, const rclcpp::NodeOptions & options); - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_cleanup(const rclcpp_lifecycle::State &) final; - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_activate(const rclcpp_lifecycle::State &) final; - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_deactivate(const rclcpp_lifecycle::State &) final; - -private: - void messageReceivedCallback(geometry_msgs::msg::Twist::SharedPtr msg); - bool onLowerLimitsChangeRequest(const std::vector & lower_limits); - bool onUpperLimitsChangeRequest(const std::vector & upper_limits); - - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - reference_joint_state_publisher_; - rclcpp::Subscription::SharedPtr key_teleop_subscription_; - sensor_msgs::msg::JointState reference_joint_state_; - const rclcpp::Duration elapsed_time_treshold_ = rclcpp::Duration(0, 100000000); - rclcpp::Time last_time_ = rclcpp::Time(RCL_ROS_TIME); - - std::vector lower_limits_rad_ = std::vector(7); - std::vector upper_limits_rad_ = std::vector(7); - - int active_joint_; - bool changing_joint_ = false; - const double turning_velocity_increment_ = 3.0 * M_PI / 180; - - const struct - { - double X_POS = 1.25; - double X_NEG = 2; - double Z = 1; - } WEIGHTS; -}; - -} // namespace teleop_guided_robot - -#endif // CONTROL_LOGIC__KEYBOARD_CONTROL_HPP_ diff --git a/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp b/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp deleted file mode 100644 index 3c57cdc7..00000000 --- a/kuka_driver_examples/teleop_guided_robot/include/control_system/system_manager.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CONTROL_SYSTEM__SYSTEM_MANAGER_HPP_ -#define CONTROL_SYSTEM__SYSTEM_MANAGER_HPP_ - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "lifecycle_msgs/srv/change_state.hpp" -#include "lifecycle_msgs/srv/get_state.hpp" -#include "lifecycle_msgs/msg/state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "std_srvs/srv/set_bool.hpp" -#include "std_srvs/srv/trigger.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "kuka_driver_interfaces/srv/get_state.hpp" -#include "kuka_sunrise/internal/service_tools.hpp" - -#include "kroshu_ros2_core/ROS2BaseLCNode.hpp" - -namespace control_system -{ -class SystemManager : public kroshu_ros2_core::ROS2BaseLCNode -{ -public: - SystemManager(const std::string & node_name, const rclcpp::NodeOptions & options); - - void activateControl(); - void deactivateControl(); - - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_configure(const rclcpp_lifecycle::State &) final; - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_cleanup(const rclcpp_lifecycle::State &) final; - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_shutdown(const rclcpp_lifecycle::State &) final; - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_activate(const rclcpp_lifecycle::State &) final; - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - on_deactivate(const rclcpp_lifecycle::State &) final; - -private: - bool changeState(const std::string & node_name, std::uint8_t transition); - bool changeRobotCommandingState(bool is_active); - void robotCommandingStateChanged(bool is_active); - void getFRIState(); - lifecycle_msgs::msg::State getState( - const std::string & node_name); - void monitoringLoop(); - bool robot_control_active_ = false; - bool stop_ = false; - int lbr_state_ = 0; - const std::chrono::milliseconds sleeping_time_ms_ = std::chrono::milliseconds( - 200); - - std::thread polling_thread_; - - rclcpp_lifecycle::LifecyclePublisher::SharedPtr - reference_joint_state_publisher_; - rclcpp::Subscription::SharedPtr robot_commanding_state_subscription_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr manage_processing_publisher_; - rclcpp::Client::SharedPtr change_robot_commanding_state_client_; - rclcpp::Client::SharedPtr get_state_client_; - rclcpp::Service::SharedPtr trigger_change_service_; - rclcpp::CallbackGroup::SharedPtr cbg_; - rclcpp::QoS qos_ = rclcpp::QoS(rclcpp::KeepLast(10)); - - const std::string JOINT_CONTROLLER = "joint_controller"; - const std::string ROBOT_INTERFACE = "robot_manager"; - const std::string CONTROL_LOGIC = "keyboard_control"; - bool control_logic_; -}; -} // namespace control_system - -#endif // CONTROL_SYSTEM__SYSTEM_MANAGER_HPP_ diff --git a/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py b/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py deleted file mode 100644 index 2db56fd4..00000000 --- a/kuka_driver_examples/teleop_guided_robot/launch/keyboard_guided_robot.launch.py +++ /dev/null @@ -1,56 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch.actions.include_launch_description import IncludeLaunchDescription -from launch.launch_description_sources.python_launch_description_source import ( - PythonLaunchDescriptionSource) -import launch_ros.actions - - -def generate_launch_description(): - robot_config_file = get_package_share_directory('robot_control') + "/config/lbr_iiwa.yaml" - kuka_sunrise_dir = get_package_share_directory('kuka_sunrise') - - kuka_sunrise_interface = IncludeLaunchDescription( - PythonLaunchDescriptionSource([kuka_sunrise_dir, '/launch/kuka_sunrise.launch.py']) - ) - - joint_controller = launch_ros.actions.LifecycleNode( - namespace="", package='robot_control', executable='interpolating_controller', - name='joint_controller', remappings=[('measured_joint_state', 'lbr_joint_state'), - ('joint_command', 'lbr_joint_command')], - parameters=[robot_config_file], output='screen' - ) - - keyboard_control = launch_ros.actions.LifecycleNode( - package='teleop_guided_robot', executable='keyboard_control', output='screen', - name='keyboard_control', namespace="" - ) - - system_manager = launch_ros.actions.LifecycleNode( - package='teleop_guided_robot', executable='system_manager', output='screen', - name='system_manager', namespace="" - ) - """ - key_teleop = launch_ros.actions.Node( - package='key_teleop', executable='key_teleop', output='screen', name='key_teleop') - """ - return LaunchDescription([ - kuka_sunrise_interface, - joint_controller, - keyboard_control, - system_manager - ]) diff --git a/kuka_driver_examples/teleop_guided_robot/launch/kss_control.launch.py b/kuka_driver_examples/teleop_guided_robot/launch/kss_control.launch.py deleted file mode 100644 index f9549100..00000000 --- a/kuka_driver_examples/teleop_guided_robot/launch/kss_control.launch.py +++ /dev/null @@ -1,64 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription - -import launch_ros.actions -import yaml - - -def load_file(package_name, file_path): - - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, 'r') as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - print('Couldn\'t load file ' + absolute_file_path) - return None - - -def load_yaml(package_name, file_path): - - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, 'r') as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - print('Couldn\'t load yaml ' + absolute_file_path) - return None - - -def generate_launch_description(): - - robot_config_file = get_package_share_directory('robot_control') + "/config/kr6.yaml" - - joint_controller = launch_ros.actions.LifecycleNode( - namespace="", - package='robot_control', executable='interpolating_controller', output='both', - arguments=['--ros-args', '--log-level', 'info'], parameters=[robot_config_file], - name='joint_controller', remappings=[('measured_joint_state', 'rsi_joint_state'), - ('joint_command', 'rsi_joint_command')] - ) - - return LaunchDescription([ - joint_controller - ]) diff --git a/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py b/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py deleted file mode 100644 index 2e140adb..00000000 --- a/kuka_driver_examples/teleop_guided_robot/launch/sunrise_control.launch.py +++ /dev/null @@ -1,78 +0,0 @@ -# Copyright 2022 Aron Svastits -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription - -from launch.actions.include_launch_description import IncludeLaunchDescription -from launch.launch_description_sources.python_launch_description_source import PythonLaunchDescriptionSource # noqa: E501 -import launch_ros.actions -import yaml - - -def load_file(package_name, file_path): - - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, 'r') as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - print('Couldnt load file ' + absolute_file_path) - return None - - -def load_yaml(package_name, file_path): - - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, 'r') as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - print('Couldnt load yaml ' + absolute_file_path) - return None - - -def generate_launch_description(): - - robot_config_file = get_package_share_directory('robot_control') + "/config/lbr_iiwa.yaml" - kuka_sunrise_dir = get_package_share_directory('kuka_sunrise') - - kuka_sunrise_interface = IncludeLaunchDescription( - PythonLaunchDescriptionSource([kuka_sunrise_dir, '/launch/kuka_sunrise.launch.py']) - ) - - joint_controller = launch_ros.actions.LifecycleNode( - namespace="", package='robot_control', executable='interpolating_controller', - arguments=['--ros-args', '--log-level', 'info'], parameters=[robot_config_file], - name='joint_controller', output='both', - remappings=[('measured_joint_state', 'lbr_joint_state'), - ('joint_command', 'lbr_joint_command')] - ) - - system_manager = launch_ros.actions.LifecycleNode( - package='teleop_guided_robot', executable='system_manager', output='screen', - name='system_manager', namespace="" - ) - - return LaunchDescription([ - kuka_sunrise_interface, - system_manager, - joint_controller - ]) diff --git a/kuka_driver_examples/teleop_guided_robot/package.xml b/kuka_driver_examples/teleop_guided_robot/package.xml deleted file mode 100644 index 179ce082..00000000 --- a/kuka_driver_examples/teleop_guided_robot/package.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - teleop_guided_robot - 0.0.0 - Package for starting keyboard-controlled motion and synchronising the necessary nodes - rosdeveloper - Apache 2.0 - - ament_cmake - - rclcpp - rclcpp_lifecycle - sensor_msgs - geometry_msgs - std_msgs - std_srvs - kuka_driver_interfaces - kuka_sunrise - kroshu_ros2_core - - robot_control - pluginlib - key_teleop - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/kuka_driver_examples/teleop_guided_robot/src/control_logic/keyboard_control.cpp b/kuka_driver_examples/teleop_guided_robot/src/control_logic/keyboard_control.cpp deleted file mode 100644 index 0b9fe286..00000000 --- a/kuka_driver_examples/teleop_guided_robot/src/control_logic/keyboard_control.cpp +++ /dev/null @@ -1,184 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include -#include - -#include "control_logic/keyboard_control.hpp" - -namespace teleop_guided_robot -{ - -double d2r(double degrees) -{ - return degrees / 180 * M_PI; -} - -KeyboardControl::KeyboardControl(const std::string & node_name, const rclcpp::NodeOptions & options) -: kroshu_ros2_core::ROS2BaseLCNode(node_name, options) -{ - auto qos = rclcpp::QoS(rclcpp::KeepAll()); - - key_teleop_subscription_ = this->create_subscription( - "key_vel", qos, [this](geometry_msgs::msg::Twist::SharedPtr msg) { - this->messageReceivedCallback(msg); - }); - reference_joint_state_publisher_ = this->create_publisher( - "reference_joint_state", qos); - reference_joint_state_.position.resize(7); - - registerParameter>( - "lower_limits_deg", std::vector( - {-170, -120, -170, -120, -170, -120, - -175}), kroshu_ros2_core::ParameterSetAccessRights {true, true, - true, false}, [this](const std::vector & lower_lim) { - return this->onLowerLimitsChangeRequest(lower_lim); - }); - - registerParameter>( - "upper_limits_deg", std::vector( - {170, 120, 170, 120, 170, 120, 175}), kroshu_ros2_core::ParameterSetAccessRights {true, true, - true, false}, [this](const std::vector & upper_lim) { - return this->onUpperLimitsChangeRequest(upper_lim); - }); -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn KeyboardControl:: -on_cleanup( - const rclcpp_lifecycle::State &) -{ - reference_joint_state_.position.assign(7, 0); - active_joint_ = 0; - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn KeyboardControl:: -on_activate( - const rclcpp_lifecycle::State &) -{ - reference_joint_state_publisher_->on_activate(); - last_time_ = this->now(); - reference_joint_state_publisher_->publish(reference_joint_state_); - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn KeyboardControl:: -on_deactivate( - const rclcpp_lifecycle::State &) -{ - reference_joint_state_publisher_->on_deactivate(); - return SUCCESS; -} - -void KeyboardControl::messageReceivedCallback(geometry_msgs::msg::Twist::SharedPtr msg) -{ - if (this->get_current_state().label() != "active") { - return; - } - - rclcpp::Time current_time = this->now(); - rclcpp::Duration elapsed_time = current_time - last_time_; - - - // Update reference only with a max rate of 10 Hz - if (elapsed_time < elapsed_time_treshold_) { - return; - } - - double z = -msg->angular.z; - if (z > 0) { - if (!changing_joint_) { - changing_joint_ = true; - if (++active_joint_ > 6) { - active_joint_ = 0; - } - RCLCPP_INFO(get_logger(), "Active joint: %i", active_joint_ + 1); - } - } else if (z < 0) { - if (!changing_joint_) { - changing_joint_ = true; - if (--active_joint_ < 0) { - active_joint_ = 6; - } - RCLCPP_INFO(get_logger(), "Active joint: %i", active_joint_ + 1); - } - } else if (changing_joint_) { - changing_joint_ = false; - } - - double x = msg->linear.x; - double x_dir = x > 0 ? x * WEIGHTS.X_POS : x * WEIGHTS.X_NEG; - double new_reference_joint_state = reference_joint_state_.position[active_joint_] + x_dir * - turning_velocity_increment_; - if (lower_limits_rad_[active_joint_] < new_reference_joint_state && - new_reference_joint_state < upper_limits_rad_[active_joint_]) - { - reference_joint_state_.position[active_joint_] = new_reference_joint_state; - last_time_ = current_time; - reference_joint_state_publisher_->publish(reference_joint_state_); - } else { - RCLCPP_WARN(get_logger(), "Joint limit reached!"); - } -} - -bool KeyboardControl::onLowerLimitsChangeRequest( - const std::vector & lower_limits) -{ - if (lower_limits.size() != 7) { - RCLCPP_ERROR( - this->get_logger(), - "Invalid parameter array length for lower limits"); - return false; - } - std::transform( - lower_limits.begin(), - lower_limits.end(), lower_limits_rad_.begin(), [](double v) { - return d2r(v * 0.9); - }); - return true; -} - -bool KeyboardControl::onUpperLimitsChangeRequest(const std::vector & upper_limits) -{ - if (upper_limits.size() != 7) { - RCLCPP_ERROR( - this->get_logger(), - "Invalid parameter array length for upper limits"); - return false; - } - std::transform( - upper_limits.begin(), - upper_limits.end(), upper_limits_rad_.begin(), [](double v) { - return d2r(v * 0.9); - }); - return true; -} -} // namespace teleop_guided_robot - -int main(int argc, char * argv[]) -{ - setvbuf(stdout, nullptr, _IONBF, BUFSIZ); - - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared( - "keyboard_control", - rclcpp::NodeOptions()); - executor.add_node(node->get_node_base_interface()); - executor.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp b/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp deleted file mode 100644 index beba4fa3..00000000 --- a/kuka_driver_examples/teleop_guided_robot/src/control_system/system_manager.cpp +++ /dev/null @@ -1,380 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include -#include - -#include "control_system/system_manager.hpp" - -namespace control_system -{ - -SystemManager::SystemManager( - const std::string & node_name, - const rclcpp::NodeOptions & options) -: ROS2BaseLCNode(node_name, options) -{ - qos_.reliable(); - cbg_ = this->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive); - change_robot_commanding_state_client_ = this->create_client< - std_srvs::srv::SetBool>( - ROBOT_INTERFACE + "/set_commanding_state", - qos_.get_rmw_qos_profile(), cbg_); - robot_commanding_state_subscription_ = this->create_subscription< - std_msgs::msg::Bool>( - ROBOT_INTERFACE + "/commanding_state_changed", qos_, - [this](std_msgs::msg::Bool::SharedPtr msg) { - this->robotCommandingStateChanged(msg->data); - }); - - get_state_client_ = - this->create_client( - "robot_control/get_fri_state"); - manage_processing_publisher_ = this->create_publisher( - "system_manager/manage", 1); - manage_processing_publisher_->on_activate(); - auto trigger_change_callback = [this]( - std_srvs::srv::Trigger::Request::SharedPtr, - std_srvs::srv::Trigger::Response::SharedPtr response) { - response->success = true; - - if (this->get_current_state().label() == "active") { - std_msgs::msg::Bool activate; - activate.data = false; - manage_processing_publisher_->publish(activate); - if (this->deactivate().label() != "inactive") { - response->success = false; - } - RCLCPP_WARN( - get_logger(), - "Motion stopped externally, deactivating controls and managers"); - } else { - RCLCPP_WARN( - get_logger(), - "Invalid request, system manager not active"); - } - }; - trigger_change_service_ = this->create_service( - "system_manager/trigger_change", trigger_change_callback); - - - // If node is in unconfigured state, parameter can be always set - registerParameter( - "control_logic", false, kroshu_ros2_core::ParameterSetAccessRights {true, false, - false, false}, [this](bool control_logic) { - control_logic_ = control_logic; - return true; - }); -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn SystemManager:: -on_configure( - const rclcpp_lifecycle::State &) -{ - auto result = SUCCESS; - if (!changeState( - ROBOT_INTERFACE, - lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) - { - result = FAILURE; - } - if (result == SUCCESS && !changeState( - JOINT_CONTROLLER, - lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) - { - result = FAILURE; - } - - if (control_logic_ && result == SUCCESS && - !changeState(CONTROL_LOGIC, lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) - { - result = FAILURE; - } - if (result != SUCCESS) { - this->on_cleanup(get_current_state()); - } - - return result; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn SystemManager::on_cleanup( - const rclcpp_lifecycle::State &) -{ - if (getState(ROBOT_INTERFACE).id != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED && - !changeState( - ROBOT_INTERFACE, - lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) - { - return ERROR; - } - - if (getState(JOINT_CONTROLLER).id != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED && - !changeState( - JOINT_CONTROLLER, - lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) - { - return ERROR; - } - if (control_logic_ && - getState(CONTROL_LOGIC).id != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED && - !changeState(CONTROL_LOGIC, lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) - { - return ERROR; - } - - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn -SystemManager::on_activate(const rclcpp_lifecycle::State &) -{ - auto result = SUCCESS; - if (!changeState( - ROBOT_INTERFACE, - lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) - { - result = FAILURE; - } - if (result == SUCCESS && !changeState( - JOINT_CONTROLLER, - lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) - { - result = FAILURE; - } - if (result == SUCCESS && !robot_control_active_ && !changeRobotCommandingState(true)) { - result = FAILURE; - } - if (control_logic_ && result == SUCCESS && - !changeState(CONTROL_LOGIC, lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) - { - result = FAILURE; - } - - if (result != SUCCESS) { - this->on_deactivate(get_current_state()); - } else { - polling_thread_ = std::thread(&SystemManager::monitoringLoop, this); - robot_control_active_ = true; - std_msgs::msg::Bool activate; - activate.data = true; - manage_processing_publisher_->publish(activate); - } - return result; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn SystemManager:: -on_deactivate( - const rclcpp_lifecycle::State &) -{ - if (robot_control_active_ && !changeRobotCommandingState(false)) { - return ERROR; - } - robot_control_active_ = false; - if (polling_thread_.joinable()) {polling_thread_.join();} - if (getState(ROBOT_INTERFACE).id != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE && - !changeState( - ROBOT_INTERFACE, - lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) - { - return ERROR; - } - if (getState(JOINT_CONTROLLER).id != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE && - !changeState( - JOINT_CONTROLLER, - lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) - { - return ERROR; - } - - if (control_logic_ && - getState(CONTROL_LOGIC).id != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE && - !changeState(CONTROL_LOGIC, lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) - { - return ERROR; - } - - return SUCCESS; -} - -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn -SystemManager::on_shutdown(const rclcpp_lifecycle::State & state) -{ - rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn result = - SUCCESS; - switch (state.id()) { - case lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE: - result = this->on_deactivate(get_current_state()); - if (result != SUCCESS) { - break; - } - result = this->on_cleanup(get_current_state()); - break; - case lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE: - result = this->on_cleanup(get_current_state()); - break; - case lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED: - break; - default: - break; - } - if (!changeState( - ROBOT_INTERFACE, - lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)) - { - return FAILURE; - } - if (!changeState( - JOINT_CONTROLLER, - lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)) - { - return FAILURE; - } - - if (control_logic_ && !changeState( - CONTROL_LOGIC, - lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)) - { - return FAILURE; - } - - return result; -} - -void SystemManager::monitoringLoop() -{ - while (this->get_current_state().label() == "active") { - getFRIState(); - std::this_thread::sleep_for(sleeping_time_ms_); - } - RCLCPP_WARN(get_logger(), "Stopping monitoring loop"); -} - -bool SystemManager::changeState( - const std::string & node_name, - std::uint8_t transition) -{ - auto client = this->create_client( - node_name + "/change_state", qos_.get_rmw_qos_profile(), cbg_); - auto request = std::make_shared(); - request->transition.id = transition; - - auto response = kuka_sunrise::sendRequest( - client, request, 2000, 3000); - - if (!response || !response->success) { - RCLCPP_ERROR(get_logger(), "Could not change state of %s", node_name.c_str()); - return false; - } - return true; -} - -lifecycle_msgs::msg::State SystemManager::getState( - const std::string & node_name) -{ - auto client = this->create_client( - node_name + "/get_state", qos_.get_rmw_qos_profile(), cbg_); - auto request = std::make_shared(); - - auto response = kuka_sunrise::sendRequest( - client, request, 2000, 1000); - - if (!response) { - RCLCPP_ERROR(get_logger(), "Could not get state of %s", node_name.c_str()); - return lifecycle_msgs::msg::State(); - } - return response->current_state; -} - -void SystemManager::getFRIState() -{ - while (!get_state_client_->wait_for_service(std::chrono::milliseconds(1000))) { - if (!rclcpp::ok()) { - RCLCPP_ERROR( - this->get_logger(), - "Interrupted while waiting for the service. Exiting."); - return; - } - RCLCPP_INFO(this->get_logger(), "service not available, waiting again..."); - } - auto request = std::make_shared< - kuka_driver_interfaces::srv::GetState::Request>(); - - auto response_received_callback = - [this]( - rclcpp::Client::SharedFuture future) { - auto result = future.get(); - lbr_state_ = static_cast(result->data); - - // Two consecutive non-four states are needed for shutdown - // to avoid unnecessary stops - if (lbr_state_ != 4 && !stop_) { - stop_ = true; - } else if (lbr_state_ != 4 && stop_) { - std_msgs::msg::Bool activate; - activate.data = false; - manage_processing_publisher_->publish(activate); - } else { - stop_ = false; - } - RCLCPP_DEBUG(this->get_logger(), "State: %i", lbr_state_); - }; - auto future_result = get_state_client_->async_send_request( - request, - response_received_callback); -} - -// Activate the ActivatableInterface of robot_manager_node -bool SystemManager::changeRobotCommandingState(bool is_active) -{ - auto request = std::make_shared(); - request->data = is_active; - - auto response = kuka_sunrise::sendRequest( - change_robot_commanding_state_client_, request, 2000, 1000); - - if (!response || !response->success) { - RCLCPP_ERROR(get_logger(), "Could not change robot commanding state"); - return false; - } - robot_control_active_ = true; - return true; -} - -void SystemManager::robotCommandingStateChanged(bool is_active) -{ - if (is_active == false && this->get_current_state().label() == "active") { - robot_control_active_ = false; - // TODO(resizoltan): check if successful - this->deactivate(); - } -} - -} // namespace control_system - -int main(int argc, char * argv[]) -{ - setvbuf(stdout, nullptr, _IONBF, BUFSIZ); - - rclcpp::init(argc, argv); - rclcpp::executors::MultiThreadedExecutor executor; - auto node = std::make_shared( - "system_manager", rclcpp::NodeOptions()); - executor.add_node(node->get_node_base_interface()); - executor.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/sonar-project.properties b/sonar-project.properties index 834223d3..f273b5ba 100644 --- a/sonar-project.properties +++ b/sonar-project.properties @@ -7,7 +7,7 @@ sonar.host.url=https://sonarcloud.io sonar.modules=kuka_driver_examples,kuka_sunrise_driver, kuka_rsi_hw_interface, kuka_rox_hardware_interface, kuka_controllers kuka_driver_examples.sonar.projectName=kuka_driver_examples -kuka_driver_examples.sonar.sources=./robot_control/src,./robot_control/include,./teleop_guided_robot/src,./teleop_guided_robot/include,./teleop_guided_robot/launch, ./eci_demo/src, ./eci_demo/launch +kuka_driver_examples.sonar.sources=./eci_demo/src, ./eci_demo/launch kuka_sunrise_driver.sonar.projectName=kuka_sunrise_driver kuka_sunrise_driver.sonar.sources=./src/kuka_sunrise,./include/kuka_sunrise,./launch kuka_rsi_hw_interface.sonar.projectName=kuka_rsi_hw_interface From 5361edc2a83291ad02aae2f10f1b9cfbbba06a46 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 12:35:00 +0100 Subject: [PATCH 91/94] remove deprecated launch file --- .../launch/kuka_sunrise.launch.py | 39 ------------------- 1 file changed, 39 deletions(-) delete mode 100644 kuka_sunrise_driver/launch/kuka_sunrise.launch.py diff --git a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py b/kuka_sunrise_driver/launch/kuka_sunrise.launch.py deleted file mode 100644 index b30ac68b..00000000 --- a/kuka_sunrise_driver/launch/kuka_sunrise.launch.py +++ /dev/null @@ -1,39 +0,0 @@ -# Copyright 2020 Zoltán Rési -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -from launch import LaunchDescription -from ament_index_python.packages import get_package_share_directory -import launch.actions -import launch.substitutions -import launch_ros.actions - - -fri_config_file = get_package_share_directory('kuka_sunrise') + "/config/fri_config.yaml" - - -def generate_launch_description(): - return LaunchDescription([ - launch.actions.DeclareLaunchArgument( - 'node_prefix', - default_value=[''], - description='prefix for node names'), - launch_ros.actions.LifecycleNode( - namespace="", package='kuka_sunrise', executable='robot_manager_node', output='screen', - name=[launch.substitutions.LaunchConfiguration('node_prefix'), 'robot_manager'], - parameters=[fri_config_file]), - launch_ros.actions.LifecycleNode( - namespace="", package='kuka_sunrise', executable='robot_control_node', output='screen', - name=[launch.substitutions.LaunchConfiguration('node_prefix'), 'robot_control']) - ]) From ff62af8938f5f1bf8ecb2bc35e799fab57e03fae Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 13:42:33 +0100 Subject: [PATCH 92/94] remove depracated doc --- doc/wiki/1.-Quick-start-guide.md | 135 -------------------- doc/wiki/2.-Design.md | 92 ------------- doc/wiki/3.-Relationship-to-ros2_control.md | 98 -------------- doc/wiki/gfx/components_ros2.png | Bin 71511 -> 0 bytes doc/wiki/gfx/components_sunrise.png | Bin 77270 -> 0 bytes doc/wiki/gfx/example_application.png | Bin 120115 -> 0 bytes doc/wiki/gfx/general_application.png | Bin 147288 -> 0 bytes doc/wiki/gfx/motion_lifecycle_sequence.png | Bin 187370 -> 0 bytes doc/wiki/gfx/use_case_diagram.svg | 3 - 9 files changed, 328 deletions(-) delete mode 100644 doc/wiki/1.-Quick-start-guide.md delete mode 100644 doc/wiki/2.-Design.md delete mode 100644 doc/wiki/3.-Relationship-to-ros2_control.md delete mode 100644 doc/wiki/gfx/components_ros2.png delete mode 100644 doc/wiki/gfx/components_sunrise.png delete mode 100644 doc/wiki/gfx/example_application.png delete mode 100644 doc/wiki/gfx/general_application.png delete mode 100644 doc/wiki/gfx/motion_lifecycle_sequence.png delete mode 100644 doc/wiki/gfx/use_case_diagram.svg diff --git a/doc/wiki/1.-Quick-start-guide.md b/doc/wiki/1.-Quick-start-guide.md deleted file mode 100644 index b1f27ff0..00000000 --- a/doc/wiki/1.-Quick-start-guide.md +++ /dev/null @@ -1,135 +0,0 @@ -### Requirements: - -- KUKA LBR iiwa - -- KUKA Sunrise Cabinet - - - Running Sunrise OS 1.16 (other versions might also work) - - - Sunrise FRI 1.16 - -- KUKA smartPAD - -- Client computer - - - Connected with an ethernet cable to the KUKA Line Interface (KLI) of the Sunrise Cabinet - - - ROS2 foxy on real-time linux (preempt_rt) - - - kuka_sunrise metapackage is downloaded and built with **real** fri_client library linked - - - key_teleop package is downloaded (necessary for example application) - -### System start-up - -1. **Sync the Sunrise Project ROS2_Control to the robot** - - Start the Robot Application ROS2_Control.java, which contains a state machine and a TCP interface so that full control over the state of the robot can be realized from ROS2. - - After everything has started properly, controlling the robot is possible using the standard ROS2 tools. No interaction with the SmartPad is needed, except for when the application has to be stopped. However, the external control is terminated if a safety condition is triggered by the SmartPad. - -2. **Set IP address of client machine in the Sunrise Project** - - Set the variable `_remoteIP` in the file serialization/FRIConfigurationParams of the Sunrise Project to the IP address of your client machine. (TODO: use rosparam) - -3. **Set IP address of Sunrise Cabinet in the ROS2 sunrise driver** - - Set the parameter `controller_ip` in the launch file `launch/kuka_sunrise.launch.py` - -Then continue with one of the following options: - -#### Starting the robot driver only - -4. **On the client machine run `ros2 launch kuka_sunrise kuka_sunrise.launch.py`** - - This launch file starts 2 nodes: - - - Robot Manager: - - Manages lifecycle, initiates connection to the Robot Application running on the Sunrise Cabinet, initiates real-time control, handles errors etc. - - - Robot Controller: - - Real-time monitoring and commanding of robot states through FRI - -5. **Activate robot state monitoring with ROS2 lifecycle CLI** - - 1. **`ros2 lifecycle set robot_manager configure`** - - Now the connection to the Robot Application should be established and the messages - - ``` - Command received: Connect - Command executed. - ``` - - should appear on the smartPAD log. - - 2. **`ros2 lifecycle set robot_manager activate`** - - Now the connection through the FRI should be established and the messages - - ``` - Command received: Start FRI - Command executed. - ``` - - should appear on the smartPAD log. If the second message is missing, there was an error and the FRI session could not be started. In this case the command `ros2 lifecycle set robot_manager activate` also returns with a failure message on the client machine. The most likely issue is that the ports for the FRI were configured incorrectly, or they are not allowed through the firewall of the client machine. Refer to the Sunrise FRI documentation for more info on how to set up FRI. - -6. **Monitor the robot state by running `ros2 topic echo /lbr_joint_state`** - As of now this functionality is not working, as monitoring mode is not activated with the activation of the driver. Work on the solution of this bug is in proggress. - -#### Starting the example application teleop_guided_robot - -4. **On the client machine run `ros2 launch teleop_guided_robot teleop_guided_robot.launch.py`** - - This launch file starts the driver, a node for interpreting keyboard inputs, an interpolator (to avoid stopping the robot by velocities over the limits) and a system manager. - -5. **Activate robot state control with the ROS2 lifecycle CLI** - - 1. **`ros2 lifecycle set system_manager configure`** - - 2. **`ros2 lifecycle set system_manager activate`** - -6. **In a new terminal run `ros2 run key_teleop key_teleop`** - - You should now be able to operate the robot joint position from this window. You can increment/decrement the position of the active joint with the horizontal arrows and change the active joint with the vertical arrows. - **NOTE**: if the key_teleop node errors, you should download the package from github (https://github.com/ros-teleop/teleop_tools) - - -#### Starting the driver with an interpolator to be able to move the robot with custom control - -4. **On the client machine run `ros2 launch teleop_guided_robot sunrise_control.launch.py`** - - This launch file starts the driver, an interpolator and a system manager. - -5. **Activate robot state control with the ROS2 lifecycle CLI** - - 1. **`ros2 lifecycle set system_manager configure`** - - 2. **`ros2 lifecycle set system_manager activate`** - - This activates all system components so you can poll robot states (`ros2 topic echo /lbr_joint_state`) or send joint commands on the _/lbr_joint_command_ topic with the following command to test moving the robot: - - `ros2 topic pub /reference_joint_state sensor_msgs/msg/JointState "{position: [0, 0, 0, 0, 0, 0, 0]}" --once` - - **CAUTION!** The robot can move really fast, with half of maximum allowed velocity, you should give a goal position close to the actual and reduce the allowed speed with the joint controller's _velocity_factors_ parameter (this specifies overrides for every joint) - - If you write your own application, you should just publish the required joint states on the _/lbr_joint_command_ topic. You should note, that the timing of the control cycles are always managed by the robot controller and it requests commands with a certain frequency (configurable with the _send_period_ms_ parameter). The joint controller makes sure that commands are always available, but you should be aware of the fact, that **commands sent to the driver are not written to the robot immediately, but only when the robot requests a new command**. - - It is also possible to extend the interpolator with a more complex control algorithm. All necessary functionalities of such a controller are implemented in the _JointControllerBase_ interface class (_robot_control_ package). Deriving from this class and overriding the pure virtual _controlLoopCallback()_ method with your own control algorithm is the suggested way to adhere to the current structure. - - -### Common issues - -##### Configuration hangs - -If configuration of the robot manager (or system manager) hangs and does not return anything, you are probably having a connection issue. Check if the IP address and Ethernet configurations are correct and make sure that the TCP port 30000 is on your Sunrise Cabinet. - -##### Could not start FRI - -If activation of the robot fails with the error message "Could not start FRI" and the SmartPad log shows that the command errored, you are probably compiling with the mock fri_client library. FRI client library is needed for starting FRI and sending commands to it, you should make sure that you compile with the real library. - -##### FRI state is reduced to 2 - -If FRI state transitions to 2 and control stops during motion, the connection quality is not good enough for real-time communication. FRI has strict QoS policies that stop control by high jitter or latency, if such problems occur often, you should try to increase cycle time (_send_period_ms_ parameter) or check if your system is really capable to fulfill real-time requirements. diff --git a/doc/wiki/2.-Design.md b/doc/wiki/2.-Design.md deleted file mode 100644 index 308a3e04..00000000 --- a/doc/wiki/2.-Design.md +++ /dev/null @@ -1,92 +0,0 @@ -# Design - -## Use case analysis - -This project aims at creating a comprehensive driver that could be a reliable part of various ROS2 applications. To guide the architectural decisions, we conducted a simple use case analysis: - -![Use case diagram](gfx/use_case_diagram.svg) - -We identified the following use cases: - -- **Robot State** - The current state of the robot should be accessible to ROS2. This includes the measured joint positions and torques, field bus inputs, FRI state and motion tracking performance. -- **Robot Command** - Commands from ROS2 for controlling the motion and field bus outputs should be passed to the robot. -- **Configure** - The ROS2 system should be able to access and change various configuration parameters of the FRI Session (robot monitoring) and the FRI controlled motion (robot commanding). -- **Manage lifecycle** - The driver should implement the ROS2 lifecycle node interface. -- **Handle error** - Various errors that arise on the robot should be handled by the driver if possible. Some errors may change the lifecycle state and require external handling from ROS2. - -To accomplish these, two connection points are needed towards the robot. Configuration, lifecycle management and error management has to be done before or after a real-time control session. The robot application running on the robot should provide interfaces for these use cases and manage the FRI Session and motion control according to the given configuration. Once an FRI Session is started by the robot application, the robot state can be accessed and commands can be sent on the FRI in a real-time manner. On the diagram on Figure 3.2, the Robot Application has been referred to as *Robot Manager* and the FRI Session as *Robot* in order to better reflect their roles in the system. - -The presented ROS2 actors show an example on how these use cases can be handled by the user. The Robot State can be used by various *Robot State Listeners* for visualization and control purposes. Robot Commands can be given by control nodes. For handling the lifecycle and the configuration, a *System Manager* and *Configuration Manager* could be used, respectively. However, this is only an example scenario, the power of ROS2 is that such a robot driver can be integrated in the system according to the user's needs. - -## The ROS2_Control Sunrise project - -(Note: not to be confused with ros-controls/ros2\_control!) - -The driver can control the robot only if the necessary program is running on it. Because of this, we developed a Robot Application to enable reconfiguration and motion control of the robot through ROS2. We named the Sunrise Project that contains the Robot Application and all developed Java files *ROS2_Control*. The following figure illustrates the components running on the robot controller during ROS2 control: - -![Sunrise software components](gfx/components_sunrise.png) - -The ROS2 KUKA Sunrise Driver connects to the real-time Fast Robot Interface and the non-real-time Robot Manager Interface. The *FRI Session* component is provided by the Sunrise.FRI option package. The non-real-time components *ROS2 Connection* and *FRI Manager* have been developed as part of this project. - -## The kuka_sunrise ROS2 package - -This package contains the client side of the implementation of the ROS2 KUKA Sunrise Driver using the C++ ROS2 API (rclcpp) and the FRI C++ client libraries, targeting the Linux operating system. To ensure real-time performance, the preempt_rt patch has to be installed on the system that runs ROS2. - -### Internal modules of the driver - -Realized as ROS2 nodes. - -- **Robot Controller** - The Robot Controller with the robot through the Fast Robot Interface. On the ROS2 side, the joint states and field bus inputs are made available using publishers. The joint commands and field bus output commands are listened to on another set of topics. When activated, the Robot Controller is part of the real-time control loop. - -- **Robot Manager** - The Robot Manager is a management and configuration module for the ROS2 KUKA Sunrise Driver. It interacts with the Robot Application on the Robot Manager Interface and also manages the Robot Controller module. - -![ROS2 software components](gfx/components_ros2.png) - -### Interfaces of the driver - -#### Towards the robot - -- **Fast Robot Interface** - Real-time communication UDP interface for enabling external joint-level control of the robot. Completely realized by the FRI client library. - -- **Robot Manager Interface** - Non-real-time TCP interface to the Robot Application running on the Sunrise Cabinet to manage the lifecycle of the robot and to configure the control parameters. - -#### Towards ROS2 - -- **Access Peripherals** (TODO) - The driver publishes the configured field bus inputs to individual ROS2 topics in each real-time loop and subscribes to individual topics for the configured field bus outputs. - -- **Access Joints** - The driver publishes the joint states on a ROS2 topic in each real-time loop and listens for the joint commands on another topic. - -- **Manage Lifecycle** - The state of the driver can be managed via the ROS2 lifecycle and other custom services. - -- **Manage Configuration** - Parameters of the driver can be set via the ROS2 parameter services. Changes are either handled in callbacks if needed, or they are used upon lifecycle state transitions. - -# General application architecture - -A module diagram of a general application as we envision it: - -![General application](gfx/general_application.png) - -# Example application - -The module diagram of an example application that we created: - -![Example application](gfx/example_application.png) - -In this example application the individual joints of the LBR iiwa can be controlled via keyboard inputs. Refer to the [1. Quick start guide](1.-Quick-start-guide.md) for more information on how to setup the application. - -The typical lifecycle of the motion control is shown by the following sequence diagram: - -![Motion control lifecycle](gfx/motion_lifecycle_sequence.png) diff --git a/doc/wiki/3.-Relationship-to-ros2_control.md b/doc/wiki/3.-Relationship-to-ros2_control.md deleted file mode 100644 index 48975a10..00000000 --- a/doc/wiki/3.-Relationship-to-ros2_control.md +++ /dev/null @@ -1,98 +0,0 @@ -# Relationship to ros2_control - -## Summary - -With our approach in the ROS2 KUKA Sunrise driver we chose to leverage the standard ROS2 features and framework instead of integrating it into the ros2_control framework. The reason for this is that we believe that ROS2 (once it is mature enough) should be able to meet the requirements for distributed, real-time control systems. Therefore, we want to experiment with an approach where hardware resources and controllers are also first-class citizens of the ROS2 ecosystem. Our hope is that such a solution could simplify the control stack, and also that any feature or tool inspired by the control loop design or the rest of the system could be of benefit to the other (access control, composite components, dataflow programming, lifecycle management, runtime reconfiguration etc.). Thus, we are designing the ROS2 KUKA Sunrise driver to be able to be the part of such a showcase solution. - -*Note: throughout this document ROSX stands for ROS1 and ROS2, and rosX_control stands for ros_control and ros2_control in general.* - -## Disclaimer - -The discussion below represents our opinion on these topics, which we developed by carefully going through related code documentations, source code, studies, presentations, forum discussions, GitHub issues etc. We do not want to make false claims and statements w.r.t. ROSX and rosX_control, therefore please feel free contact us if you think we misevaluated something, know of additional relevant online resources, or if you just want to share your own thoughts on this topic. - -## About this document - -This document is meant to serve as a detailed explanation on why we think that our approach is worth pursuing. It contains a discussion on the more important features of ROSX and rosX_control, with a focus on the capabilities of ros_control that made it invaluable for ROS1, and how these capabilities appear in ROS2 itself. However, this document does not cover every feature of of rosX_control and does not provide a complete design on how the same functionalities could be implemented in a ROS2-based control stack. That would be a large enough project in itself, and right now we are working on the KUKA Sunrise driver. Nevertheless, this document should provide enough justification for our approach. - -## Feature comparisons - -### ROS1 and ros_control - -The de-facto standard tool for implementing real-time external control interfaces of robots to connect them to ROS1 is the ros_control stack. ROS1 in general is not designed for real-time systems [[1][1]], therefore ros_control introduces its own light-weight framework to enable the modular design of control loops. The controllers and the controlled hardware are then represented as a single node in ROS1. The tools of ros_control helps with the integration of real-time robot interfaces into ROS1, and some out-of-the-box controllers can be easily reused to set up the control loop quickly. However, the software stack of ros_control is not as feature-rich and flexible as ROS1 itself (e.g. composite controllers [[2][2]], controller-chaining [[3][3]], different update rates [[4][4]], one-shot updates [[5][5]), and developers and users have to make themselves familiar with its usage. - -### ROS1 and ROS2 - -Opposed to ROS1, ROS2 is being designed from the ground up to support real-time applications that span multiple nodes [[6][6]]. The extent to which this holds for nodes communicating over the network is of course limited, but leading DDS vendors support shared-memory data transfer inside a single process [[7][7]][[8][8]], or alternatively the intra-process communication mode of the ROS2 client library layer can also be used [[9][9]]. - -Furthermore, there are many additional features of ROS2 compared to ROS1 that are expected to enable the construction of complex yet stable applications: lifecycle management, improved launch system, improved parameter handling, security tools etc. - -### ROS2 and ros2_control - -Given the aforementioned features of ROS2, the integration of a robot driver as a standalone node and the utilization the standard ROS2 tools and interfaces to implement the control loop becomes a quite intriguing possibility. If the main features of ros_control are already built into ROS2, then in theory no additional control stack would be required (in its current form). This could result in a much simpler and more modular and flexible design, and also no additional control stack would need to be maintained and learnt on top of ROS2. Instead, the control stack would be built on the ROS2 framework, like any other ROS2 application. - -To evaluate this, let's have a look at the most important features that make ros_control great, how ros2_control improves and extends them (as of its current state and roadmap), and how an alternative control stack built on top of ROS2 could provide the same functionality: - -- **Real-time support:** - The ros_control framework is real-time friendly, and provides tools for connecting the real-time control processes with the non-real-time ROS1 system [[10][10]]. ros2_control keeps the same approach, and does not build on ROS2 being real-time friendly, i.e. the communication between the components is not realized via ROS2 interfaces and tools [[11][11]]. - -- **Hardware-agnostic design:** - All hardware resources are integrated via a common interface, thus any robot can be controlled by the same control stack. The respective interface is being improved upon by ros2_control to provide more flexibility and access control. However, this feature is not driven by a lack of some capability in ROSX, and therefore a similar design should be possible via ROSX interfaces. - -- **Lifecycle management:** - ros_control provides a simple lifecycle for its controllers. ros2_control uses the LifecycleNode interface, but not over the rmw layer. A looser coupling of controllers and the controller manager could be achieved by using the lifecycle topics and services. - -- **Resource conflict checking:** - The controller_manager provides a safeguard against multiple controllers acquiring control over the same hardware resources, meaning that control signals for a resource should come from a single controller [[12][12]]. This is an important feature, yet not unique to hardware resources. It is also important to avoid conflicts and race conditions on all topics of the system, be it associated with path-planning, navigation, visualization, HMI etc., which is a challenging task in such modular systems as ROSX. Various new features of ROS2 such as DDS security access control [[13][13]], lifecycle management and the enhanced launch system are likely to be powerful enough to ensure that such constraints are enforced - not only for the control stack, but for the whole application. This is one of the more difficult things to achieve via ROS2, but the solutions would benefit any ROS2 applications, not just the control stack (and on the other hand, the solution could also be inspired by other applications as well) - -- **Runtime command mode- and controller-switch** - In rosX_control it is possible to change the command mode (e.g. position -> torque and) of hardware resources and to swap the active controllers in a single iteration of the real-time loop [[14][14]]. This is important in order to avoid time frames when no controller or multiple controllers would be commanding a hardware resource. Implementing this feature should also be possible via ROS2, but not trivial. - -## Why the driver before the control stack - -*Note: we haven't found any ROS2 project on the web that would aim at the realization of a such a control stack, but happy to hear if there actually is.* - -If there is to be an alternative control stack into which our driver should fit in, then one could say that the sensible thing to do would be to first design the framework, into which then the hardware resources and controllers could be integrated. If there is no control framework yet, how can we implement a driver that is conformant? - -##### The main reason for starting with a driver: - -Our goal itself was to have a driver for the LBR iiwa in ROS2 that we can use for a showcase application. When the project started in 2019, ros2_control was in an initial phase yet, and we also wanted to try out the new possibilities offered by ROS2. Thus, we started developing a driver to use for our application, and through the process also evaluating ROS2. Spoiler alert: the results so far are promising; that's why we are continuing on this path. - -##### Justification for why this reverse order could nevertheless work: - -The advantage of our envisioned control stack is that it doesn't need to be a framework in the same sense as rosX_control is. The framework is ROS2: interfaces, lifecycle, access control, system supervision etc. The control stack would only need to use these tools to realize the functionality required for (optionally) real-time control loops. It could be just like any other ROS2 application. And since ROSX is in large part about decoupling components that can be developed independently, developing a robot driver component, then developing a controller component and connecting them via launch configurations fits well with the ecosystem of ROS2. Of course, it remains to be seen whether this will actually work, and we expect to have to modify some parts of the driver as the control stack comes into life. However, this would-be control stack is still far off, and in the meantime we can easily connect some basic controller nodes to our driver for testing purposes or simple applications. - -## Compatibility with ros2_control - -Despite all the lengthy discussion on why we want to move away from ros2_control, we still want to provide some possibility of using our driver with it, since it is available today, many people know how to use it and will probably prefer to use it also in the future. It is also nice to have multiple alternative solutions anyways (especially if they are compatible), so users can choose the one that fits them best. There are multiple possibilities to ensure compatibility: providing wrappers, adapters, separating the outermost interface layers from the underlying logic etc. However, this is feature is rather low-priority for us at the moment. For people looking for a ROS2 Sunrise FRI driver simply integrated into ros2_control, there are already some implementations available on GitHub that might suit their use cases [[15][15]][[16][16]]. - -[1]: https://answers.ros.org/question/134551/why-is-ros-not-real-time/ "Why is ROS not real time?" - -[2]: https://wiki.ros.org/ros_control/Ideas#Composite_Controllers "Composite Controllers" - -[3]: https://wiki.ros.org/ros_control/Ideas#Realtime-friendly_dataflow_interface "Dataflow Interfaces" - -[4]: http://control.ros.org/project_ideas.html#asynchronous-control-components "Asynchronous Control Components" - -[5]: https://github.com/ros-controls/roadmap/pull/52 "One-shot/Trigger Interfaces" - -[6]: https://www.apex.ai/roscon2019 "ROS2 RT" - -[7]: https://www.eprosima.com/index.php/resources-all/performance/eprosima-fast-dds-performance "Fast DDS Performance" - -[8]: https://discourse.ros.org/t/dds-implementation-performance-benchmark/19343 "Fast DDS vs CycloneDDS Performance" - -[9]: https://docs.ros.org/en/foxy/Tutorials/Intra-Process-Communication.html "ROS2 intra-process communications" - -[10]: http://wiki.ros.org/control_toolbox "control_toolbox" - -[11]: http://control.ros.org/doc/getting_started/getting_started.html#architecture "ros2_control Architecture" - -[12]: https://fjp.at/posts/ros/ros-control/#exclusive-resource-ownwership "ros_control Resource Ownership" - -[13]: https://design.ros2.org/articles/ros2_access_control_policies.html "ROS2 Access Control" - -[14]: https://fjp.at/posts/ros/ros-control/#controller-manager "Controller Manager" - -[15]: https://github.com/KCL-BMEIS/lbr_fri_ros2_stack "LBR FRI ROS2 Stack" - -[16]: https://github.com/ICube-Robotics/iiwa_ros2 "IIWA_ROS" diff --git a/doc/wiki/gfx/components_ros2.png b/doc/wiki/gfx/components_ros2.png deleted file mode 100644 index e95a71f1b5a02c3e51f501db562402913b2d7544..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 71511 zcmeFZXH-*NyEY0amI#6hA{|7LBA`?ODFJEHYiI!#LT>`07eOf^y&8J&1Sts}M5Xs$ zLQ{G|?=A2xp7+`Be)itqIb(e1-#OzjhQr{BbFMY#-LC7p=lZOsB1a0M0TB=okSfT( z(jXwX%1%H)RC41Q@Gqe2{4u~^giacAQUu6ex>ewptL9*3FabeX#I3Wp#K7-29pv?# z2ncTfy!=DhW}k0LKyZ-c288^LV(N8RG{o)^cSv#T_oiHUD>S)EmT4ogr} zO4{&|lKv66ON!@46A3W;0>)$;_>oQUA^nX8!6yK3r*{{9Mt;F6SMEWH{HL1$>sFX4@7-i}T^TQ90Ul$44H$zNSO?(Qq=1i+#?9FTH>kf-Tt4jO zQ=NfWi6z^=XG;SA016cJ-LLA=J4ble9}P7O;{pkLv)wiu4s9@KTTjcrRI!04L2G^r zgapE*|NLL0>t_-4Ms=z5Zf~L*wDS82?VKa7kiF~=p(65-M!fdr{Hl~G*v_gF+C;NO+BWd`x>$|z_O*8yG5f`DA8@s;fgc)91SIbio!KlTDr$zWJ13P04PmMlRQ*UeW)0R=WgXes0 z+&uf==XoZ%K5kT84{VBzM7J1S0Y|`%EGObOZGL^ZXY(COhM|`Z!VK$idM8K|OV_#- zjpSRRtVYWHu3R^JEi~hnMH^q~dARXEmI^UoFhr#nS2(g3*%`Ev!x1$4?OIp_Iy}Mf zEl((7iB`VL^y}6P5pJR`jUH1UNAKcBU!+%rr1u?UcUf2dxRyeeaFR#~Ix8Z%svNq;keL2nkQdH1}G)r2E zoiu}oNRRo;Y2KCdVVG=$@2oQI=?0yUGNw*oaOvm+gngV##ddxPnB==`XlgY?4cWx# zv-7w}fBjk2)Z3sjbeZN-ww{^sph#|yp2^s(S5S(>V8On+G#VRimyo-4+w^z8DN& z{CMWR@o{e-(z#c}aJ(gilGE;Vv#E)a+i-k@e#_uKC5bz0%Y=Cvy*FrF2)m??w$TFu zqP#v33Z<^G5_g8SHi(W93%@4rmCxylMG?A6B(rvb5hUK%r%Wh0bR7L)XXgCtbJB(5 z-jP!_F9|>hI-?vzE9_*A@m;&=|R*&9t-Mm`1#q+vVG&9<)t<-Mj+Z~>|g8~WH z3sFWTyi&2pK@AriVQ%c+rtAs(6FO`%hzrCFex-1NtbNnTOIck?U{fEwM(WNl;KZWS z`EEeGZNs{627k!QH#jzXa3ac=vib*=V_|v`B8OhZL$l@8>()B04Fdx%M0Qjrd7zxr z$eNC8Gh*F>%kNn~DupCe~n>Y4Z*51wGNZ4_A`!IJ5$* z%6|xslKl2AM|!G!pN7Hm)>w{jNuIgJ)0wTX6whYZ#sjtwkXEqG_tYWQ0FpZ>V@!-* zzwef`B}uYwgM@2J9G7u3R}smTk|J~)Hf`5FBiug}&WH)$mD(Rpqj|Z*5 z$W_snMr#7c3OMhY#@4@ZN!%0xMLTw8t3eXY0GGp2?`-ikc9}xhXE9P6i8xP;SYubZ z|6{=TZm|3vkzulBtTM|*$S+riEH&50e7EbMK8q;sxlzZ6m%E8c;`1@2I*a|-4JS$t z2AeFSq-0i6@WkB+u~U!2X7vgk`lK4uqNKw=UoGvRgQWP)*D=)Teba6ja%;GUC~mSL z!n@w>OOnsPA_UVMS5#Zoisi_##NKvL7)!OodsvqcOc|)wpDBU%SDUuViwx7BeEc(+ zbZsL}Ju-&1B|6M=E%|mr^_)g)PtV6dS)wnopS$?R|oA5T1EM$_ag4wmZ8mE z9S{tYxmESfvnE+n9;RkJMyc-@R>KXc7F6g={8VjNDA(PfKPa}2sWq_hS+*N%HPtw?b%JjRh=ccGY2qc$B9&9YP=;tO2|fl@TQ@I1eYRm#gwYY8Tn%A zWe-+WAPKM9hB1fHQE+xmvt0=LGUQ@xPa~(R+9dt>q|Tr;$xyW3+h+V|WjK+7vD?^Q zPDpG9YTXi&@U48Yvu=$H53O(!qnh)y)mjQ8a-lcpDpH~yu~lnTt+GDJb(!DR^k8kF zjWMgitB*Y(K9v&?7VHt{*j-*7xHl~@wb^@pO5ACDh5W3So9TK`e`WY!$VOK2S}AY>NM>lSkL-yY4<#tnnVczzK;A&Lj&;>`z8MXOUJMtLFXS zYzU`UtX0v99Wmf}9r`jR6Yxow)tm&g*YqOJ4lF)E!75q)Z^MX{@ht<($a(e)Zw| z+MxKu?E^jgLCWAxIt>W5GLFHrVl$1Kv|s!8U8@%#hr7G9Wcd;Vu3 z(Q+$|_6LLF?4qyyD$Ab^Ps_Ea!W*)aljf&|M|M0grEty%@qU8~<4Z2?Ro2kaur!5? z^l8yXk+Is;nbflJ)Gu`AlzMS@-W#=b8B*OskQA0?z+iM15^qk- z3|0{o^D`;S2kOgJRwx?odC9;Z#0iG0@k2XLDqoBcf8K?xSJpAo{qDZ0oB-ZG*n7L?2d)WDUpwe-Xv)UcR2k0)N}x#fI22=U)RohE?@$ ztCM5LJP>5EcA=If&;B|_=wu;M45)LM^8T*)+4w>P*eR3>Elg+q4n_7Gk8dYt9khNK5e9-uL)IR%nwZz8UrjyYiqPu{sxr>SwU;d*9obMQMg}4UFpad zMz(kQvitW;!bLk^18g_q^)dy2B~f&?3UB&%P4UBsEbufPGF?^+Uzd$iOf|)ge)GN> z)|QbCjn}5S4g*;T6Wiw{zmHEsZjh|PGS<4X`<+LwsV50|TP~aoKOc4u17&%zBy#UI zcR2@_C}h+!cIx-<8C=f^J<2@j(JT9TyToY7_Gew|%NVJyLeVzQPXEtqRS7q<)Q##B zDayuj${AyOGCZF1-M4WZ8udOe8nJiFHW-VFI_Nx#vV0`Xp0lp4Y2DMFP4{9!-TZ`| z)9mC4t35eU?BpTeQzIeL>NY6nt@}^E zG5Vgp=fNLf?EfbO0gAJzREoL6+uuE%E~ulQhbcUNawXGhlZoF4`x25Q)r^##U-AA@t74jL$6&1? zPgC+rIu(22L3_4RQCcI|;>-O+38Y|o=y9v`!dmMdC7Uu&z5#j_Gc2@G$evDehq!+i zvRQd8Ov7KfL0h#?_j7{(>J!)pN%7jSWuREU(&jrY(d%tbL_OaINbl{ywu~ z)Id(TzK4v`jd}MS`g4%(3SMF+TdlwNtvP(d*(*-Q@%JL6ZtVu?HnrzWn@Z|@x%Qqr zjF3$i@>Zi@;wF1rg-*%|+R9*(pi|RK2?UP_Zcv#t9-mN#99}Q=c?|^o4|NPKxPf!d z@x#en8iv{+mP3;Iaz?{Ra&&cb5pb;JVD`7U-j!f)0y6Z@7te8f?x(+^K?e>XQ zKvp`daP)I7z3-n6^h2`;`Uo=pphubuaW{uFdw$)|t5gs};vZsc2iL9&K@kkj$MQx6 zjbX?*0qfCMY2=RAf%>rB^55X(oiZrL9oLgD`>Ef+4kl<(o7)nR{2P8aKGseS3U4ST z-j6#pkZlf|QR$MeUPXIq;MmwcnzT!+=5gmS=|B|=8C|N2f|#8$X6ebQwJyf@kJ(4F z)vEmRj6J$2AMJq@Ipl|vj*t4p0L)i#?GyISufBv~?G^*sfQJHHz&GENm}JkPq@4Mq z_2D$x&%NL6FL~Zlf?usn#@=7qjSi*DS zK3Ub}l%9_r>T`seR8HM8$<66iRTY`t)$vI+t4lqAY2^2Ca8RF8!+8dFc-gghWQKqW zb{(_tZLex8=OI$2ZEc?UE0Ll~7P&oc`x@9P0PAj$Afls8a&S;R*^|_KOz`L;P@~vv zhv$Jjk%!boV=;}KMyG=@jWN_=$d7k9FSnrdZ>lGjx+ReU2<1aLew@MTj2@(M1*;&p zRFCZ*e)|S(NlkE)c+s2TQit4`^IU4`N0X1GbAL_Ar{|}0H>%|k!S;&|Pfm(vo2sVA zW=`4*Wv$iN8hno0pCfu%g9X^RtM^`y88zGiQ0-`g&oNCLSb+GQL|)^8kxP)(^HFB{v^KGnTc6>w&n9td$0XE{&FfdjQtP97dRW2Twsm2N)cIRH5 z7f=ajBWdr=7|hMg6-DOD_Q-c6j`zVi)x&N>8D~&l@0T}_@;T!7I7yod@uAbmyzZ|Q zBEDs59mNXF(=WG-s%~5Mi$$!D2r5i-zvE-CES7z~J^H%?2*j@7ecnna3^yfl=ALx6 z?U)B}9*#p|G4IX`c?<=ka#1giLrJW&>z|ofVc)M0HdI*~c-5i8d}ZH*J6Qk6UTg>O zQ92YQ`7agloY!k#)ccK+XQ#eRCs6+Rtkp+{aA`McF4r(1#Eu$9*sYK5Ax`3WRPe(O zPRoC=&hbzh3{~0_CKW53)84-}%mp4A_Pxjvl5p^IIx`>AELQkU3NBpj{1F+IX_Ag4 zLk635UqNGS-G1g58aD}r7HVcgIsUNye3SzXs^NZ`NM)_zCLL*2J39S46KR(k^7x?o ze3ajE2ZWBWaZEm)x}%&p5lr=@dW}StOk&>=+h1BZ5@{6T9YV;*dpDWEHb_Ubn}Jb4 zFs$QIL20eO_g|3HF!K0(3Z=uLZ>r8x>b4Yv{pcpZx-*#F@AGuxD9pQlVQBbAej+R1 zY6ye3;oRe&vU=>3fmq*_UF_stTK*!>pZ)^IxvQh(rBlz?H$3JFhGE)t!+iPIW-nf0 zoxSa26|$AC_C3AvPJ>PQ)hwUw;n#W9*FE9=?axMHy(thI2nuZHZ+dIEpE{Jpe!6fs zz<0_K#ZKSwo6oZQY2wyH<2y#H92+8R!8t(d?) zttjfU7A!7oO7>r4880t;?9KP^NBzTI#L^9R4MtIfyKyLtQk-TU&XGz}?8}Zcb#C7SoNQj=!L(eD=YB~< zvBd&_fDgmy@{YR0;8EW-TNwBCMkwS>5`QT)mt(;e6NN!KRen)#AcS9LMy*rJwd(y7 z6XbdudV8WtXJ6ctPm5~K&ftstoPng{wXU==N~8egs!Hs>G!I@q!qV|v?1>swp5x?` zHXLl#p%j!<+Hah9R@bMN;p+|j=iZQr`H$`AXc1Hi-@B8&I?kS&U~K?x)e4TZNDaZt z3wo?DYl~@m`xbBevJx3KYp3(QdBQHf)6ft6qWnGFPOUFT9`h$=#8|&%a)0`yh*762 zx7TPf6il4|_;oJDn$}WxcaA|yO^#DxUlC_;ZR}IsIt)VWuPZpTeeXG)ygwkaA$J{4oU^ zJKQ)rD!s4csao!bnFCHHjnRPk{dmZIsd_E8evE8AU}4z+)i~K4rwO{rG3P8@BKr~P z%F>*wL~JYMa@twnKWkM~e*2wrbSO}lAefBeKg+79b=LdW+cnrZ4w>FyBM-xe<^kNs z^BmHETNv+%usx`3bcVCZ1+xxE;?2x-9jJzL@`w*g6*nM%yEAlKJZpp9i1Z3V4SQcL z%Zw`_WvM=;g5_uqmtdxD=I@x2SemZ%`Xnc8v+!ooV6=r!oHWe9^S~eK9`DHXG^Z`m0 z%2#=w+a_2w(WNO1zWGkW0?)1ZNslxe(7h@jIq&U&s zK8w2AbAT+X8Ri!1jE!c`-H#8Oy3Su7PI8N@$Xa^L-sV(oMv*nZ3de6ZH7*k>Cti+=lO~7!xQh-{7}9r5h-EReM$AKmN8{V~f}sPXxuu=|;N`$D3hZ52s>& zmmbZnrxmgRWR%I;BGu*ArT#N9231Z!bFg8)YbQp&%O(jsrEqq)2qE^^_wO-tL59!r z7x_IpL**SjyWc;l?c*0-`sA#+LP-KCartVnadt~ouGh~uj97vFqOV~m{8r;gi|lf) zl4%m?S%mdWr`?Kgm8Sv2>3u^p#j*D1gMzV3rBS@H5uSY`FZzWwT**sy7we)Vjm9Dl z!1hB8aQU&R7yT%8%piGU;=$g^O*=jBR!&~5f~{J@U2oa8=39|*J(+g*o+LXL(i_$k z-rC`$*O);0exHuW7CsQ^?JOK%qXvyTr&cloRMU8?9MNu%@v*tOJTJQlbhO9T__RRj zsxpLNV?7HwG2Yj%HMqkq{k9{|F0oM>+nZqtdx$I0D@yGmA3QIx`&9mzzZ>cA(^Cqq z%IKmPbl>m&`HSp+j@@qW>G>+n9|h?!?8}vt8hom6=sjrOx+s)E&sEzz*+P^j%ySl| zmppPVb%>9(7=_A`|5lhw( zb$HOsC-Eo8Bty`G8jpidZ#`m>PSai|KtbB12rG?01`t!d z^&sQlY7!k=Ta(Ku;RDgTj9#mvS*t)5)tW#;2JM=3Mc9-PHihSuN7m!ymmfD06rUfU zsSQ{b(~buOWhf+!PYdU>_i@Q?V?pt|llKf(be7d7UMJ?^q)xxi2;^8xwrOIZbjOh8 zA$#H2!+(;3m-?hXGmww}%{>F+AIF3L`IWxxe6?@BTp{{cD&J zcFUO^e$llp5l;mcKFdl3jewQzbS?aFaJ_1l!P~K&;ZkNC`cJVme@>oQUHj1sBm9Qf zcTz~*yB5$XuC(c3(D&kW_P;BGmvZY08h~J|Er|lwnW{Hxu3V~^{Qn0kW~5RG{&03y zHk{6KC{MLd0A(=%D82txCq+=uOtbKOx>Pc6{-=`JA4*KS-a*y6{5jPZ55-jDBL1gj z`+uwa0#+W!u4p^@19d5{O1UFlm+dZfPszVlqc7WS1yLqwHOzJ?A!ocCF|cod?Z(@E z69=A-oZwPS{*9m@lMwBl@!S-{)WVBwXB+7+2VzqN6h%7&)atFvO}u(}$MWkN&n+9* zryAN0ybkXHdh;i>RI77oA;(B z+u3CV`;WGa1q6kv*nX_-RP~+9@7Xuu(d$hY=U*v^buWG5Ke{9UUJgt|Ao)>V+y z3?bD&Efg?uc_7kU>Y4xUS`}qlu=Wqg8Mp2Q+?ngj?UmG*_MO~aWU3^jLVEk)}5B>q> z8ubU0)&uM{KTRUU0)YYl3Kp;Pl|o7zPdZaQH-u@$JSy==^AQ6D#6dibM?X^CmkpGF>)e|W6hDcw#!S^XWoh#EahBG<1E{e|cFo*Zd5^C9o^1y~ zf!lNWar4PI5?Yt3xqJPu?MinS>LLPUXd=VkwO^IcoVA9^B)gR%u4)P_OBh6GSN8O`bjog@9rcDRLvz`$2-W` zY@#0jPv#niPCWwX_w%xtO3Rp`lYJaC_lLrhlm!wxSki(i)is#;)pewwLe%cxtNC9B z^*Z_;#68}y7;mt4w%g|_8{ogYr&dBpywerW<~vLE7rij+Pier-QtKl;b+} zKB)9&2E5~!@cGgFVQ22qM%|{(`XtIO$!C4=yjZWIbvzJx44(&qS z8plP$IiHQ1<=j#mP!m%4erOu|r)1FKjIm)*D6{J;V2X!TZ(E%-A z++psIVlrQSzANasAYTW#-E_IgC^k1Uk=*lO?K3xGa8x0NwI(!j9F4ZcjM7V&mWZf` z^d=ZOe#Q}H4`6-4iI^t)hL z76Ta#4~;Y>{41z^x+hjg0d&>ib+E47d>XE*_-iL(RHl?lpjgU(dB9r@uY(EmUP+6I z@|;`Tl-V5LAWSsYY{5KDXM+vz)zS<6qxsBxE87@-r-+L|T9nRT0LPjo?gAB3*86NV zUmq=k@En@VR@oaLqKy!Ds-|6%;-2aa+SPB%QnB&qSGEH-Db8ttE{48up)8;#=O8Z# zB_#gyx@*{xS932t;~+l;^g|m1ZY~8GSy5AF#opAYb+)Vu3uWL1cw;ts`@!tbMasWn z{P|qGbb$B6fcOVE|9o3SRaUr2C-F+B;2ja}MAji$GEsn2^I`iU384681ck_LUUuwA zk@<3pYbxJ;vz|oQm1`spfuH<+c}~GV7s=xiNSkYGC^a{yY}@Y-S8h8jw_*|^B+kd_ zlQdPu1W+Zs(KJGKHgN3ldp%MqGymMxv!W7@-RxTGP6oYdhYV4n#5@-+qxx}5O0hq| zEK>pt2vQ$bnI<3nRL$sd95wn)Gm+V`pMpGK_gDC4$k6B7 zU=(Q|mEN%1Y&S+{y-)Va zG;&_&TpMHn)sNT#HFQ)q_~SK~Nz1$(>R!$Df#Ap3yBXe!5dgnJ%`}v&>;y(na_+vu zs5z7re>%E;8^O=ZVAq6qIjkbN4O0O~%iY3#cR-v2&B3m&xM3f-uRK^KRK%%4ZZgNb z1M-=ZnXCL~6%S3D`^r5aXdiFcj#9-}uv2un>Xg}>a97gCmeZDSC(I8b4( zYOd0<0|d%Cm-apKZPtKuoz7yVobipvBE7uA&OVh&yg<4G((RAW<{G9s1ZdfUAK8+h z|H`M2XMy`b8&uh?6WNZu-0G)wC;o}O_J{aPUuT+fSOB~adN)AUh`pQ7?a%wXQXKBC z=0Nv_$a3VB+8pPQq+bayZ>1g2*Z5fP3`TR}CXZ)sD;Ys+-+_LrbNp#tH}o!DFYAoUbpdwOj=J-P+IK879~gQg_6LuqB-={D&Ga`AS!s`a zvw)dDMXXY?Zqlh7Taah8oW#3{%P;}9b{()P?7hV)=)=BAscj3*9gm--HX!P!SVfP; zI7n@G08j}$tbKLj#u`xmdYG#v23>%U`kk(H$KI3UL4p3AM8;Vkg(bh*Ah!NPB@q44 z(Zei2x#(p0yc{MpRm4GH=RrZnuX< z9%sM-BMN5p=LZDPLvlbFW^N2i)jE{6-3R2n4X57K;23OsMTI9;na#M)&biS$(@ z4hp52?!9V$uQRYh!~0BYP18)K81Xy9mQxo3EF95*!P(Kqt+KTu2eX%eZXi$p*3=kE z<^PoeAQYT@+cGzJJS?_Dv$_*0u&G(Q#ZtMaR@Q)4rNn`d#va_YetE-If{#_^DV95n zD3v#|GC83v#^Ucf0_b+xbkPY=@VomL^YI$k&0)ACi?l^$m>VCs-9e4&7IC+S3AbIt zzD@!nU7xh9{&2<Yy+PJYp6C352VGN|$=5&~OI zLbSgX%>1cd`6H1-#!52KAZ0!05I8^_wV|ukBxS!b!o}RUW%g80fPGjHaU08B2FH!A z3{yCh@b3f(O)8MbNU`UZ$*{ud?5clX8xxSuiVp@Jl9x1GbmK)4v<_`Ac4uTljaCMD z*iiNoP26WOW0BI%#DTIQ3;KsM+5NM;(P!aJf$?zz{Pr{TE3v=){|;=j`5w5Es)J}= z-u;v@wl_Yz^Iv4H0}vc0^RMl+)&QD%`ZGTA-F$iF2N`h_*65i~7ZezpICa*m8qe2SV0Tb}N5w-C-`BEA1)Ptdrz%8D=9bEAfv3BoK7XO0?3 zzrz*VknuDEs6cCA+Q}M(@eR&$_Rk*8sp_z#xhVF6RV(mfdA zf+=f2r0~Nb*>yGYQnb~=U1~B=eM4vv6Ken#nopi{0KsXKmm&oVt$$O45CZI#5``D( zPL4eSW7%l!Wm)Oa!V)7{MPPw?6LMD{bUhoKwF;^Y$)}B!{aCY_n>6JNH3l^M@<-0% za0a+|Y+Qy@{;GMZdoFJ0j(zGQ&|hY+_N|}qQ{!%F!-2l@>kS||{9Ru*3b5~8DWDSyajU9PFJ@~c#`H--Zk7md*%9VXM5}jIzu|B z)^em!+X)v}$qiQz?mG{D60E@d6O3RJiML7{<6g&UL!gT!*Y5nvR&%9=<*o4X($>$@ z)iDCA@~O81$VYal=jak%J=2xoJtYt`pF$es_j9P|WdVKB`O<1QKPo8?DLuKV8za@G zITmyP)`$-dd_v8J5L>GG7no(!1!A8m#lNC{BE{}c zvC4Na#4?1%wIA}s112-kIMPN9p^@qD($nOz)R{yP`mzCFSYf_Opm9RHt`?mpxV{!? zN{k@rbgaHOKb;nY#kM;HlWxJ3@*A+X?_i9WonEc))k*P?>u43{Ws|hiN0o7&^c83v1t(^Ae&fQG`mzdOv^j zoxoh5O;l!Cu1zv93SHn0se?Z?)x8O2?4;ijL8Z zA=+X1j}V%Fs<2cCm{a3P;ieb+6QEAhyYn|#ccfDa`L~nSntMo>v=yqPh-`?KB13(4 zN5Y;z2?b2@?_&BHJ5yV8w*1q-QkxFH9Dms^5B43P(U)^gS3c?M4gp%- zFo($=9D0S7eC)3ixNQMeMIJ&ULQSwk_LYK7f*qj@BE=Nhbx^MYg-H9LD_7C4+Z}0l zJT`W%(*m1)e+N)a^`AAJpIAGu7FRg0YFq|%Qihi=L>@14qEHnQQj+lYIArjy6O4jFoP&(#2-~x zY<(!MgY=Std{7}f1A0WiDRS5RQW0I}FVZPVqzp5pRZbMB8knEyyO;Inv%1N&@UXy& zYxrS~pzUO~nLdH!Ik-uJ_kpq3w#*^ECzQhL5^}KVDTBPJJPtS3eXc9Uvc0`d?;KgG zkG4Tr^JK&x7bY0f3fcs#Y|GiMPgLYt7fog_tE*CS>L}Uz0*8uh@hAHOs<5ztTU7c0 zSYL}bu=}jiLA^&J<}fFD3a|iKnuE)~gBV@sPkurw+Ehj(=)NW$abPrTgu> z*th(oPe?zY$mu}a&u%bGkx866BtW%U)_t6<@e(+lliIr(KN$z5DmBWbX09i3gO8*!P6DpM3>%8uzRK zTw}Q=CfOF&Nw>hztsU`5%(*dv$9SXsDTmg}aoI+}#}GaaU^EabZnUIA*lB4k2S{Io z)A#nwM(rCnPK619Q#2vb)7ffs5+<#oE5qJdiKIz_w&eidA#6KQ-cp5*G16ImJR1F2 z(J;NytcT{%aFzKZ7+ixcwWIw)#iLSH7YLw~mEQ)Gc(03?)FKz zngvc4cZVGtq0&rQ)TV> zxKN-c*d*TtSB(>%!lZ6|G{Te6ThklEgxQJ~dW2@34^zi?GyAZ7lTUh1PjIDKPUqmj zSagn{&vpwHvOz=@dtd9441$!V0!g%o{+_)=9IOneZ-#f*Ty4baVQ?ghzTw9H=)EuK zCV<-;)1e>Ri|4!n=sdqNlKf6uR?UPh`qP!D?hf{>2D5}a=uw`4+qs^xI~sR>s&=1K z1KhcK+V=vF;C@!X$TRX(y(EO#+T|E2`eYA~cL;u^U$+F-I9EUj;EMIszbb)%x4^QCkgezX~p*XrKdd}uYV+=BA(zCarV-tQnb|wl#XFlHgtLI zaRl%s;rdmzn#K;z#5zSfT$hXu4m${tJ5|0SGo3CvqZQ~Jmo%@P4m2QXjpbCY7Y#Y&u?|6*9KnL0&I0 z;CTU){go-Th!sJ?S9SA!lEcRU@+@KLSmXUKfd5#jjkbo)yw_fj^4A>(01eY^{5ZeO zcz>dxt(CF&zP2;AaX?uGoTjl6c$=OkB@rNC7aEs}kGcy-UQF%FX{U8|XIe|zlZ43l zJl(8zbwk25FFPQBq|8Q5c|S&q@Et&)8$vk{gdSZb8)@FB2XMdr6xSJQ=%CF)dldJZ z#_d*GsLsb3;P?;wkW^nBmbXyo*yE9>gDqJ6aLQ>~WY`5J#g?TT_^F$KISUN8+mn** zBiGN{kPs1{+ysb#8I&A?68PNq+@!VoyI2;LxDRm5<)?GE>dWm{uAwM0kBz8RrlB`e z)$i>L^sCUNN+A*AC+)B|Y(J$CzfE2S7)dj>Idy2Ih9I zxGP1O@iU}iK>K>Tx7hIyH&@b?poc~6JmbSg95sdE+)Ys)wg)F7?!|ySJqoa3GC*hq;{Z5%`R9wW9rziBY2?`mu*wg&w z+YNq)Gk-RxYKCAQ`LtFx+o~n1JcE_uuzLVBf3f!Mr=jb8GU_KD6{X9}#4A#*exYQW z6%3O|rQ4Lzki&bn%YN4x98MopvId}YPA37fEy3&+DK#nYBfHvF*2AhLI6zbr5gD zhxgjMkWmFJ^Wawb;yaJ;Nl|l83fUT)#f2A*a+>^{H+SKRQ!p&SD2JI zI8h#A=W>amh1jOQE;KGzvZ|&gv#_>&uVX9|5cL6zV+ZQePMb%|IytZr`IW!0K_lgQ zidDx*i8_ykRmf#2NC^-P`HUXld$~I5+p;AQ+T}?UfDq@1B4O~}Q#WSMlI#K@2v2Ue ze^W~^B3=Z!#D$kutr@LfLs0V)TvF?Yth2ZL=Q|1&GSHm_pKWJZB3`}|nsWGvb4(|I zLgN|;Ab$1YS={%^z@?GD(@Czw2-}^vfzp)?ps!kf!|mOV7Zaw>Ig6yA_qD2+@0ZBw zJ-~LRCxY}$o+C&kx6t$#1-NiW+o9g&7K zWc^O(aQ96(rhjV}5WSR21ejN=j93E>WuYkYy-cZz>-s9-hHf#+v2cM~z!91Jl9O|H zOx)fQRQ6XvUMe>AW&`&%Da387B&9&Ny}QbU4dst0K6wIY+WJ@4yDj|)rK_-Tpb>sF zaMr+^c*w&?r_2Z?3iRm1a#j$J?<1HBC(`XGe*k2ZL7aE`e3nw+ktf1Pwv$3_t`yyw z-Cw?Ks|@r-g5f}9u2Z5B+w@$1b((HcK*K7Pb-p^Kocv+{zaE6nAR(FNK^bq`jy&&g zgypnbKL9!)f~Ap_cGs{&@!ES=7KEEPq95f6=H*mMO>dQ3YYYP&$|}}Qw|CUT5>e2% ztWBW)Qz?6cy`MRmNl#L|0yj@8idy9a;bR0qX1vj$H*C;d-|xPhl2GvW9N;Mdy9A}j zd1t3jtMbx)BGMQURC`vqMm&<$@2b+m4O0X9!KJ3XwQ0d{_TgzMaITS8{;6NWPMS7Q zP-xD$&66HZ?=D!qq2ydj6@Etw%D@kvpp;&M(#b?tn1mh%&x`^~I7u7fZ*6O!*NXj- zj=T=)2HMtP9_`s`(*eo+?0@)@_)LK9kYn_&^eoGRO8_F8rvlVtKN(ODCRIxfz61f* z=?fH{wwkse#IM@>&dQax7{M@wjJ5k>z%i@?%!a*0EEjW@!ur@3l_qo{t-RSr-P_Ce z6WrdfiTjDAWb6dhP8d6OJVqKDdvO@5fR#h0#z=vag%Wey8{TI9WL1NBt1(-PTVv}7 zKv0xX29#_UU~O~(GkK7Wgb{x^DGu`4Y{(1&&YV7dy$Yy=Z?Pt6oQ|15%;L!cu$*NA$i@#Z zoGWw^)27s?UzGdT2D4GB*(WW8E?xUdQB#`mM9G!Kc?!Vmp8JbaRM?<=#;slM>Tckm z4CCy+IporX)_`FD?JI@HeZU}jO84}ruXdJSDi+K@P4W4bGb&7X&$Eb|i6fHDR3o3Z zr4e1aZ>se|llTE;Fy~Kj3$GZ(qax9dsdAJz+8+J{FZs>%UQ+Q)$V6HOk83(E0h0wb zgc;n-9S462KhjzcR}V`y)R?n`e>ZMGYn z1#n4=uMn;x!M02#5NTJTNr4hw2D2KRVR&@>s}wH!dB&P8${4{h={s^BEMu#=)C-8g zhqbvsZUg;1bdJUXt>st=i|#+&nMtX3jg73Eo zF1Y*n_2fKD+YwMMUN#3m%cXvN9YzhQFi1pQyw#dr$Qe&x6J4vc<= zb*iZ`6~bT)7HkT{rA9h_<$Qah$PI#%;C2(xsSLGN{qwbIrW-HP!VYyOEJ023uM&%%=?wB~VTv z%<3~6$?oUnO&;D?mM+0Q$gd0HEr`?3GC`Wdy>*tsES@VzR(p@>IUD-vUO1$S8l?_o zm=v7cr*{R$yGnHsVPoW_ZNZ8Ith2Ht@3{krzNc9Y07Mg7}Pyi!67Wa3BPDSHOU zv^*?*0n{QhV=*2KDSp+VvC;gHZ&`Ef1CkcMl`?qp6nGPX-0c3+r^_Tb0hHfwpR-fw zagRp=xYIWKW>Gd!4HLsfMYb_1oBieSlD(hLP zFl{+$Gs(5xTz_B6kHgN?{DnOZ3sG{lcx^%HwcY4)N>eXD7QzkBu13+vNYw)k8XIRT z)WrbY+IXBbS(p&Wt6w>LNeEpFJJ|2$>#L*}b*cVqWrOJeegUpWGwDk2i4gA$j3j(` zMS9urTCCdrPoa0$zwjzMPwidwrikXb$f(ouYZbbdF)SLA*< z36IFBa#y?ZMaXp(Zl<*w#xKY(vtD9Jpdv#fr%zw`*u1W0?$naxY_OJ;cz2Ig$-!O| z2u^QeB#buddXq0@rAMMb6%7yv8A8J}sY6Bd-+1;&(g{ugSnv8%fx}|hz>OFIn$$i8 zH&>+I+w0D+TKagM%%v|{-v{U%wVe5cYY9wU1`0GDH^K@=j@tZvx9NLly7g{l(=HfW zSanW(qEa2dtSxfbmCrafmutIm`S^1|tRz6Bd_hHCs=hl>jNm zaUV;3VO7`r#Y)N|wfhEr#JC-o)KWAuXq=l*>NNe1hUtr6E=lS-f#^IFj*l|35xu4H z+r15`sF%ZLT%~w*TGP87Yr!(hua>1+Lq?0>^~Xy|o+B4*Y(T-0{Soj%l&TDWoKH?t z+2HZQT~0Rbw@TB)6yG}^$A2kIf8HP|n75?_5=Pd#n`xh9{K{@mj<=aINvVUH123j< z#*6KL$P^Dcc|RnOUN#8tjnh~~`UT33e^sck*@gI?B6;$FmMQE#EI{x)79+WYHUR77 z7d-)VEiGKWr{&5*w^gxaj$uK2q{c45FwKWNvb;(LzZn(lm^&xH15Dk3N^pp-zG4@^@{HbLsH{zxWkW*s`N(BxaQrT5l_W+IG!;oiU z^iFHrI;c_g(P{-JQKWm3v%sI0n~h|Y?Z!?JA3N2Cqg))(U@g>Bbai2L6gZyaaw--v zAqu=Lq&B7L*oRx_^4&bgshX<5!5|mbPoNhCH*7pYN_$BOA_0i^pM6-m_0Bb(Y+uVA zsy3zn7kh6W4rSl}|4Wy;B55I^P)e3iV=HSEl6}uIRE&MeGA70n3R#maWZ(DfnK2}V z?E5kd$v$Ietl|4UyYBA$y1w`4IDWt5`2PO*{_*>>4#S-9^E}_n>-Bg(pGT?dj4ufG zgAr?@rg-z`e^FTfH<4p+{_27K2fYOC%m+d{-!g_ilIRR;r^OR0T=GL%w`vJMltq%> zmcatQ0NZbk4j$5en}t7tn*yL>D*jdIvIihbEpGcq@FoD9Mph;o2rd-OhG24p3{-w0 zZjo%tL7^rGPnO%^rh^2b=CIqu3*tGpcX+{WIGP9ExNlfI5h3C{FEZYl=E*DljvmxK zstV!Qf!(cT2bFlC62DVo&7iK0$W&4&@@uYZy67AN;3Hm)5XBS&m~|lgqF>ycqHE;S z;TeZTe68OC@ML*3@%dGud^`Tv9bW!m0d#V1BFIgigtDK40Nzy_?@agP9aaf~up|5G z>GKeowFm%>5AI~5ew97Jc4Mx)(z5%CVVxJw6C5^vF=)FdD4KcyeRU6RcpvO!x5o>& zj=7Wg5(F*6Am*w2&YQuXplT%Ix$A=BkKuP zrnAINz!M$^Zy|6?0uQA3#tNt>v5SM9r6+Rj+jYaiBKRWsCRN~k&cB;munu^=kwUfE z6hv#xW&@q{{n@FDFj?1yp^33S%wxvA4+%3Ji8i3jnGI$^w<0@GVyq+;VLQg$W-sj> z>@BA&&CtSVYC&;j57dC1+nY5G*8qoybxw88pUfhCkGCmu?9J0Fwoeds2;--{qgWbG zuO#YeGwWK@7sMc7pUA&xUKVS&1wVx_`DU#Nc*LfTJF^#gHPT+f(Tf!>vlI_x|2?QH z3ZCHtn7Jz`Ti9F8x{)de2P|qi%nN2S^-A%U^Ng}MpkUt5zhyEz)*PblP1@d%21Zg( zEs{Me?eOK?yRSzTm`*YpJ@ZL?_W4A|vv0JZsum8~tNNgx+^YlNHVB0*YasPiL3&#~ zsIb56c|)|^e%8BSkhV&{JMC+M!tz0-`(9^lYiis4;(V}YXKuEsnpk_@p!h(T)F228_M;$+`uPZec-#coFm(0y~bpF#F{m_Sek;I$Z`imYa`XgkHGy zc^-iC_UW>+t304UJ2bG0^O zIa#WB&%rpARB86@?LdjC!rsnoa=O+L_F-^P`(+Il`8gR>TYX9Z?b7OVo#`wMBfpDG zY|I@1jP=$av||6z@$m*Yg3+^L>lHw&y$5yPYbw$+k0R4Rhi0>1&t&*Go5y2_DioB@ zQjUXA9z&OT@2;DuyyR!#14AmJgem2-$cC<63Bb4h7^4KtYJZ_gR?xwKSOuLIL_I>n zqbd)-W3&qZVsdPf-Qxw#IU~ncf;`&oUOgF#-D>d(#Y-0eT~=zd2P(R@;Sy_s`OBx# zw&ja@#%^CLrfc_>ocFRPc{%R;w}49Wa_OCylt=lTiMiQgf)DISqt#`!Ot3FZVtJF@ zpn8Rcigo_4O64IQ040gu%dsOpI>{o^R_Oixlg}nGzZef10TGRlT0lXg(+i+(ML5vB zC>ycIwgdQUvO{KJRY#I$F(33*#dZywP)Jck|smw^DG9HF&5}>-j-j<<$q>W$C zgzbd7(n!wWI2nEnp^~I{%j@U!aj+WBi{DrmDpscU+$zQpc`U-tXDsvF_4?yKv%n9P zATYvmvp@YPRgvjkFu<@n<<`r}lu$nPR3*sJ8_k<2`V{#Z6c@=BD0ZjG(JE?`M9Oz{lHQx*B4!i; zsTco!^qx<}u91yfp;lHa> zus7IQn_h&lOww!Mr12nM{Hq_G)LiLt>w$v#ERxC?XfrLu4E{+Eb&SxDVimg~q|w#D z=cBJlp^2TwEj3BA*3+xjN;xajUtXVsds0ZR%M3GF7su$ZL|=QuS~AT3boIyATqYLk z4Y25XvD|UW0K{iUg--n*wC>Kjghc6oUo1O$d@&Ms#SCVN2|13q#&uiW{5A2sC1z6& zZZD+5bfG2i&3sCViOv?(pQ>6A?39=cNx?4Hj>P?G?MMA0Po-rjM@tkYrp1Bt>(8C_#GM@U35u(t|6Z}T&q1(>uK7z}bw#E>+|>tIyr_(+ zKOyM3R`gPe=Xc-lYM{Sf6ISDHfSnamlc}cs4rU#?FA$g6%JW8#qUgKfh49}VzL-pu zXgzrr_He^Zapq+kTSW;wF0mbq39ccj;s-dXH|t&B=}^$u^AhAXyOGb@4OYi=Eedx1 z`oB-NS2(!O-L3dDYJz=(z0fKi_3c{h$4~wDTIcNQW^xk(iQ=G)MO})Zf6jF?A851^ zvb%+ZJ_GxzjVj;CA@|cy0oa^-%padYAt46>`8|@v-@AXRQJYl zXq0HNavZEEOrb#W%=oyWybngsG70q)W~#~cTqE}F&?H~kmxS!eGvaFcoJl^ZC(p$x z0mj6IH99)g3dWJ-PUKFw`NX$(GF&gMr?}nC4Hb#r<9a;UB5|Z5I z!O#{WhrHGyM!F%YMmPyX!145X*UyM!0sw7^>5^dR@2eU5ZtP=n1N6{7fNf*-4w&yV zM*<4o(Zd*p=rdxXHQ3Kx6Z~>)i|5%qlL#vhWu6-_Dtpjgy0Uo>ejl*#r{OTfwpKB( zf0(zq3Uwj}qU=jrJaasM?)m#S@L{nN-Q`wV7UgCG8QZH(Z1DZlDoScCrCo1ceHP^Y zK^y0LAKb`}x({WSG^_L4^;hGTJ))4)qLDu!LVwGIz(T=Z{f}EKoAq+{I>`=8sSU70 z<_|NuFER(GWpl*+Mb(7QKhwsy6wXt3SM z9^V-g-7kN<$WH=3jkTnEjF>AKyR2q|8S1g+Gy*j@2Q$&3OJ_>tf{(D@`RCBk<(Iq? zBzNT%{Yi}hd}V#fVDw|KkIT)v3!2D1X8LoBxFA03vDep==7?vZSHM?Cq23hC!?|Q8 ze(VCQilC7$U%kk)vPpdWJO}GT>DunS(XBwJc@+5rtl44waZ;0wp-S+8QmLA5aS81` z*{|0TPq_qTnW*t}2p>xp*d-yNf57HAiTU!;ule(*`!e2eL!;367W388qqmmWBWL3?FXvw8X5Y$k`YQo`^W8<$*kze(Ux|u#I&;BLlW2z!RJKZHdIA^T)0@|Z(0y)7H>`at!>coQz zR;meRrh8oMx*rOrquo+%PZpY(zZ9kP$6xcim-8qCUpyaQeB;HV$*Zgkt$nBC@kRJ_ zgA3F=Q4AjdVm^qx$Kh@132|sXeqFUzb$tVX@oTbE@WEhE&F{N*#a!mzFxOao&3L2n zJ@nX>UUQ&fSh{T^$pl)yl|1j}?G&g!7nk4iJb2OfIK{W$qRn^o2cWnHW)j&@cS~Jezk_95ZmdsgfFTtEFeWZO zwf?!7Jr!UNXmG)cSe(webNx~=}i=zeuw)ODtW^9vMLum9&k;%JaLQb5Uz-~@oZto}*Z>6#R{ z1M!vbeG!m!L)(vLOEZ5+()3=fg92rk;?GLk$M_2 zFML%yQ&xbL%6_kxwftJ{7I{$Nv z*xy>Ar_b=V?E)<$i5A5JK<4$9yP#{##`!hna=5`f?D#Ota@+4UiEBiKlT?amP5b8( z%tn=(Cy-k3CldhTZkcMN6d*R(Sxo9=lDj=ZF{wzdmGI^9f;t^G8B&)ziaJQA&k>MY zm4Ig%6t1VMP;*!ZFv?UeI($rU&_$1*0xbyH6-c%$pUQo5o* zDt&)T+|@vSuV7!B@g!Y^&R(IL*a0hEphAumZ5C*$k4T#vQes++g*^n|)f7I1+LG~?wDJAdf_io;+v5v(a5JW zZ`BBYvSn9Eb`C6Te?>7x34`@bcBTNc%k8Y}&-H7!&&z#WN%*XpoWPE**^9Xy8TztY)S;|BOl@REg;k30++Z_5#T5G zuP;f>(5X#eLY~vwWccfkd+$UO|2z2V7&;kS9YJoWbD z`xzzjlNoj=v`yB)UmhEU0<@@M#FGS>rB~+bDTrX5gc|uzPz^LiA2xM6yRx@T~$ZCfV63}OL_Gb zzTAu9La)>AEsgHW47R}noLQ7l%Pcx8LBRq$9Yy)kdA0*L5X;oZFC8gsr#rn3Fd~d+ zZynL%g5gb-rS0w2NrD$TStr`-k^u6stE5X}aXmvZQZu-0-Z{RgiZV~6_{m{Z=mf*- z-XVM*PjSmGesk(uWF-H{zskS%>EqrEFICjQY@FH}H7EYv*zkj^9>$=8&q0uREU}`; zdLYjRaGf8}0g^Vq;8Q2daf7;b(Q#+ueByAzV%}wk5gXHSN4daWt%W%`Hy?THo|T3? zwae*O4)o7coTUS|ll`7-!+Y*IooFQOaTF+H?CPrNU2g7G6>q0S>jL-m!D7{hDXT}< zie;;Pk(p(=*q1Xl)nLNFObi3>^@*4>yBZe&?#!a9I-(8SC9eVQxeA<`1pDE--=%<5 z5G6SH!InAM@gpxn9J#gQbU92_TA_B=Z<^8x@c6TR*A!3yLk3T`<6fI*mLy_SZXil{plXHr_4nFSUeDei#L? z+*rvi;?;a7OXQY+-5#=P2v{Egim}ckR-s-Py|}gHW(K+F>&ZE#%xd7i_c#~ActDfH ztfb+=(YrqYn|!k+Nd0^MV|_S{%jCis4y)vyaL3u)C6``%MPc|nbveU^jT^&(#_7V< zE!=0hmS;IYSE*zXX;?75v1wxNbMjc+34ECHnM_k_TQtI%>%rh!p+SX{`74;v%f`=o z=ps-65#1PFB47!1d6!b7R0|E8o7Kgm5Ge~M5WHNMv?qVIvTLLyGXVd$H~|=gcAWk& zy>;1v&bY3f;Y`qqAosCT7w2L$&{2rg$+Ue)h%gdXD*Y0lOP&u|Cg6rj0X9=9WL^(P6k6p?P?*+7R$iJ9IAZ+ z)A(VLrQP1GbuQ9(Xd38i(9h1XeEpmy#Q<(msPxzC1- zed3)P7(ojVl)2v$t-C+ETm$lJ>KKzIbDtdv(#KdA6{-P7h$nU7C^9&37MvNL*}Lp*F2dVS zBACstW7&aD>R3S7Ys}{_TWozlIl^v#hHA9CqFI1eIK2zx>4b4s9?iTcX*&hLF~WqQ zQlJGZ+-*9#8;;prF&>vu~lvAao(m2C^D3@i zFOfQql9ec!&3-3+_qY>USoQ(VoorNj-yO*5Dql5n#p<6CXzy*;KUD@hr~N_;E+Pa! z<{xspzdmrW;rgVk-3C!2r{k6VQgPh@rZ~4m0PLlhxL`_Ad}qS(Ircmc2elG<1i7_e z8*wV%fLWCrGo1s(&*|NWo;UiSu({uRYasj`Ol1u-rzQVaE9_U}C@|VuH%B}W1uX>>5Fm;_OjQIZBPiWBV^`YRsv=l-xscV`XLht<|3&SplvA zOUkddm0vuff1l5lK~ys{)3o$(w$mCuo0tFnI_(i6@<~^_0ZF$pz}J)Nkh)Jt2v$jY zg)wWs+BL^U9MJ<5X_Wx=ZuE4-nG*O-ps43^mTC0a{nI@?5Zq@nX6}izteT`^jx!1CJ-DW@s9q4EXULLz=weUw66ST zAc%~XCyHGzlhLO&KGF(GgpE|JL~+JoN*AQ$P?<%zVKIz7YVox6R1U^I$1xa&$uZx`?DE?cTE|}MVXv?j>QM=ayUcyx6qIz96TVgMz)UUVDxSB_9{B_6 zqmY0Z6XzFDS*X+Vq*<)OxHk)RKTE4dXnsj6y1{eXy@fmb_WIR<0>!Jpxnz;HW z)%TWnU2hWS`|X|sQW+i_F1}pT%XIV?`|>_o|McE~u`q{rxJo9&m^oaTvk(Od=DA;k8qlv!-oG6%g8sP7A#>~ts2QJ0EER2WS4W)) z{gnD0&go+<(L8!V#P%JULfw;kakOMPzQjdowSegEQLuZ_n1-MX?bwLIwf;GulrstHhp2Z3_bZHcSZR zKHud1Rx8gIp*L|8ajdIcyt0kK7+mv8mn)(xr}kyW5(6vL`Ls!(_TmTXb0lB)+{L_z z%jpe*XG%>qn<+3$7}9$g81S&D5@0U5Um-;tEM6u$&s}I8?Ow?T+h0efi_Ftknf?-M z|E(o^d0Oq9&ivINd3h6&_RjaB7}d-8rW`9s+U#nXt&=W@3Y z{>?dEn|Zp0#F*YX>L1rt-+$Ee2SQ2R%SYvhPq$D;>|A!{tfdJIdwud`g$9*a#WEfo zCqyq4`^&p3Q{O@owNc77uFYH#M|yy#1!|$fZZSEgyL@}X_#8NU|C$8<<7{%`u1uNo z%k9U*bX3a#%T$bfmC|+;$*93zD7w?a87Lse4P?<85@ViQaM0Pfv7L%JLtR>N2^9K@ z5tjjDBw~p+u!j`%>sM+YWner(Wm%dp`$j<9DME&F1jxm~Zstkml|`_&z%)W>_;}aZ zrGjOS1(zz9k0&_-2zoI{`V>rG$c(r)-I}hY8N#|>Nak(*LL#PhS_kr6Lbq!%zTXJ5 zN&Bx`@w>hH|Jb~5{)2dsx^$g51Bq{{4OsJhAW@R2=0oE&{<{qUbZUB48!TpgcoPS` z@#j^vnAvU@;hps9Uq}MbMm=%X^)TH!hqzcg4kI^#3#`a|1EO-bEZGjCF#wbx zWLkd=+QscPNueSLs(a#DJz(A*(C8z@Q zIU$Xe`E4FW)$eiiKyt6@@^GNb4*=1%6^?_+o8Ql+7ur@+L*^i;QDNI+Hs&X@Sqb)~ zZ!;h2kCcf+Av1eLf)Fpm=5=AAUM+p;H!cGP3N@a-K{I|o; zDI6cb(#wE2j7Lc(#kUU_;`DezuS$3B9dMRevH>{~iy^MFh9LUJuHKibo1@AB^6w#m zCSNq4;TRNegChL*?+pX0mTKR3FrL!*GbNyi!D~`mgIvV-9{?6$t`FSmD_i7_0Hs2+ z+#XjzJdA*WWRi4>GX;A%U5qjl$qDH&vOUdKOX@6wMgYR(K;`L|$?t;7cG=TmRA48 z^g~P|G|fQvPG1~BNep}C9S}E#s(zDbN$RqsV?Obtq>0s8=CP_0sq;i+nrC*$=8BfU zWwu28jO}3mJ*ry(0TTcvH}h#8?NT6u8%6C8>wvHjX#LUr&)h}fxUn$Y8+TGh@bVJq zxiQ|IsRT&!cHz1G^n0i7eDMO_L~|Og63k391BMP{xP>Z|^Ys?^p8S650w+7fmt8o7 zZkW_ch+SL%3CimOpr5Q4`}Fh66CyyIeQ^*}EPhb-EyUC7ZG5b6R89)@a52tqCENiL z4AYGq1S^B_Vozo;3)56w>^Ow)B7t=%G_1LQA65V%AoYG3djx_pU?xmNX{nZEsU+aR z1i%8o0CjNBgr_F5;jzikX%re-z|mR&cBRZz&C;s1>gNa;0S4j!{dNIJWqWxDWut?VKi;uezD<8XhgXwG`|$F+q4@uez2 zElps@-b1e&L?r$;{(5uDd8VxdU^Jr;@&dduK7fM6<#rb2zKIVhPbYt2tyKVZOb#5D z5}!mQ03svw*Ma)55exD?gi)6y4u7r}?S+pEe*lXF^ePH+@nh3s3r9E8m&KePf;R=C znE%b0iE&ZDfe(zZ!`LVQU48^Tv9|mMDhA!5qp2Dq{I%Op^EESrNas`B+!K;UfbJP4 z!l@D;g^&a|#yk4BzAU&mKHtI9EHqrKkwHsx>EmR9_u;`WZERXR=mCEaye?#91&(RM zWYKYZUa9>t6#Nc%XT}Af{aU^=7AvI853YX-Ae_Ii{{vku5U(;0B?G|bm-ZBZ0yHZS zp#|lffrd^OsQp_3GRk7(Ty-$8QUPFg++dB4_~O9GauskNwt)J8SLA~52d}90b9)c~ zQ6UWhUs&WlzoPM-gymUhgCxZWIP@yo15>BplW5%ihTtM&9NxS$$&Srq#RpPdhW@bz z9zs#f{jro(m28!Sn4%;P_l(5e{Uab}z(xcl49!~)^w@!wmdle{>FJt6tC8zh0K5!u z=dRmztaTbSz8VJtWHnvy2~bvpqWCOiN4@qIMSvfV3mJe~|FyWuHvY(LCETkAv4Eaz z%<9|Z&+l?U3?7(*()Fk)?vDNCwD51E!+-8){|W?zF6e)7bo<*T@c;GB<1ZkG^6#gB zzfuSl|35dJ`@iSwo$UlWIXf_a4)*|1ViBMsK}98xSAn_>AH}WZ5w4^wgjyP%W4>Jc zw;2*jVg!{0wPIu3=$+;;Y6c!NXu*I!2*3t?pk0DK*awz`|M`RA%0Ymu9|A>8JFvj& z>jIqR7B`Rf2f>cp4O`m_O3-Nl&^NS^SA72V@yT+R z44iWHzrr;C)!k2_0szi+lMCTzb0Q5YIwF*VWbUzoHGPQu{hWZo>$jPucA9-4DPwt8 zV{E?RRl;ZTK3FDtJh|DG_nsx1<;yn9BrS^%==`Rzr@ zwfZ@uISGtW%i-_+!mpIhvjU(peWDkH1yaC^b_A-RO8eqmMURiM`q2j)A=* z*w~CumI<^cOOFGC4e;!#Q~tvd^_nq^`+!{RJq#urMqok7P>MWB2I+$@&jS6(-@iVy zxLYNyrr{_#5Z&3Ol4`Bf38RJq%sz+^+VkT#s==`TQHH*43=$iDuE z@nsZn()=}s5C37nDf{jB7*75FKmLC*GA$}lBW|R8PhhL~aHFnASxwh&b2y;pZRJQh zO4>rx1H`Sqtl+47*ksecnXIWo9mcknVRL!&Ui7%h@L8k!f^7dEIbxyFazGJ3883I5wy^v5*hdm+IV#H zYyl?x#b08h9E8fjD{Je3Gl+S56K-~ig^ho70UMGHa{8RMLi9M>K7cmZ20V-1YIp|3 zd-gJp%&jgfEYWIl%vvRRmhQGn;F4=sJ8oDQ2uqdb(tbq0!--miUP8+%VM`7PwXN5& zx($(Gb zG2(XJ{>59nMli*Ctwjv&;&!C!x5#yz^+>quUe|={^F{ZFPnaCYQxQ5|im!e-R|xd@ zz=)KJSEDp4abU(M;pSo_rB&3T5(LmM3Va-GiQ=|_Y&0MqGG5fdzUdO`eSZ;rB#2SK zUWcyG9?DSVGh$pAt9nMz)2%e3LJ8cinnYAiv`Tx#MshoL?8JVY&eP4GC>8q&ObL1_ zJOLfgu@yc^D1nap4BQ5752N`_f%>76WtU(FqS&VQhTli|ZgVz?phgy-uQEXO2}rCl z@MCHK%8}ji;vC+X>Dv*p{lc3&n1~TV;xJW-j=E^WS}^fbP=hlrgy~O!rsXSZ?d^>mPP z^5|^!61aU0L9tvD%CA9t5x==OviQq$_F${7(xQ_U7>vfzUby**N3UqXcP!iZ0-F`1 z!>r^ytsCx`0%Z7EpjT|X2^j1l@F_b;X|NB@w3Vh!rxIX@pb8+nT=NuolAYvO3FTuh zV_QyR26`^ud3!n4XvrwjgWjCzcormxFutct4OMQ zmG06c;5@K=M%a-py8=pePxFqTOS!Gw(UM+w6dihJ3h_+(n}UXwJBC$u`}uW~(q#w1 z;{-#qLTBR)NpMP#f_aY9Rq5a2-k5ROEVbijaJy%QCVuXkSvaM;`u&~}ac{I)>g!Tj zOahx#9X`XJ9k08vD>45OYg+nK5M{J6(dvmWtE?scyq3^`X>kEktuw891t zcu#j!hzbD7VUr=j&j`)Y3PwaJen&q7;r_C>2x`d) z5(YrRkD)oo<=K%>SFZ~LwFe``V2(xuI1x>Syx!Ob8~OzRewX!RDuMQThvO{4A#tAj zYevo-hA+BU{ToQYxHCTOFD2GP^#ufTOxS1^jO?(1E^{o_e?tQ!KdL)Lm<3bCh4+N>_DnerV zQOyL?ANcsBCA4h@$tj&*NicQ+ZYbBZ4#GTLIsKJ`hjvOv$iVNBCh6%&fm`quQt$Y# z7xAN8>-@(M)?)83ymOp6_Ko25zEV1;>#tkeFzNB#AyW)ttKw@=TRLZY-mM@0J1o^IZB9 ztO$3By%zCXbba0<)Zuv|*RUn-#!%Z+N;5&$4UMLmk zVKo|V(aE{6W9vzBRWaGROXRz*V)Ef~>An&aQ7un7m{;VPcfzs1LKOS`0r$#SDfP{w z1*GZK6q^ffkEFi)!wud$841!u5mUWfT47fcktl+YN{q7-68pCFh_p`$EV{- z6({39DG7v0sEbX?Np^M}#K!@;(rr|y^BTJ5OYI|Ei&fU|79O9wOeeh<_BtkCz2q(W zkvH*`D10Q@ZJrOPTQbO(o;z3{3&^hKm8#ke4Re93m?>LgC$l=7J$sQSqkN68JJ~yc z&=9`hEag4GeW5<@(G(Ee7!4|zh2i4X7j;MQCeN!?K(cE5rn$VqK}5C*a&Zat)As?Q z*6m=q`*ZwoKba3SAgl)@MxoSHDormEKUWXZ4T?Knx(VZQ@!0$dBLAKM_hV$7hUg~S z+srgS>b%yN;?s9#6XECYwrY*Y<5$#f-r&Azhs4J%Nj(FxLYp8y?N9RCX34u-erplS zuCE>jd|V!oq?3+pOo1xYy0>6zWR~3xmW5hTj4l~oEw;9=`+bow-%jdhU+WUH^hYNh zlt7;DZ2rt!sOHb)mhAOw7XHJzJWGET=|A1j4j-97bjkXb|u z&xd|sMo=d_Ja_|t5tUo>avSA*;Z*z zNe!{DdH09C(U|viePov0KXXPv^}~T5n^UXhc>YBL0{^mWA=aCO&fm*jlEfU(yZTRX=){7Y3Slb()$8%N*-2c5|#t zNF{gF08bSkQmxNnKnBrjIGbOLYHY|Y?5s3E60_s4iTT5pT$Yf_{W#5JNsv*8=5cyo zGk!ZRe|ORH`TcVVD`VFOR(}-fN;;`Tg%%iYweGR8L|d0mW&JLU{90O#QQ;#??n7cm zeb?614M19J5PSv{3|;A}-2c>NXR*<2GbC4|KWX`YQmG=Ca>%QFz_KwM0Pa@+|%gLY~jwR;<9~ZAW8sqT5Kh^`ZrTQ4C`%2xl@&oiMQh~f` z*txjIluqKnmu90?f%OZ+p9p$0z>I$M-d+c73OU62Iy$0`{{6{KJo@8i? zoKHFEr`|-?EV-|6>xHb$$lN0wt)RS%xMS&Q9ZOlM8L`fOZ?d+zVSRDyR29b+I`TuD zx8nkOi8dqTeWLB|qsE}igOauZs+B-Mm?3}mmhblJ&nNzweCZ?FSUj$rfFikx`rbgsQL{hw%( zhPe+W_`L@{ZeVjEEP}M*wneZW`=O1JB%xE5{e{*l6m@4(oQlqe#PqrsS6ii!vN#*Q z2#!a|fQ~8hG9cQ54OO>pc#cDj9FRwe_z_^QPq662-R;EAb!)ow=#8 zr4)CaPChKVQh)o?QI4&iCmlDEDqIq<*IpsIkjX+y$2hYo`s7` z8H@v~0!-&6w(8~N=T0`fM%#DM8^eR6rBL{4sTKdy`!#(vU|M2FST^gij#utW14tZL zyIr?52u%PZt0tjlkJ=k2G~bD_%H7-l3fIDT!kE1w+YH*g zYs`4gyLNg^?Ci6X7uPJU2VSy@DTE}=jk$7v9~h4>dSM315otK;RTfwtNd7@;H%>M@ zj;&*;*{a2qfJLM*ITbns1AG55aI~Sk5jutTa_A4y< z_WY34_7}^o81(lyPwX+8(b4;<6w2noBdTV*ph8MGS~*6+BZ-AlpAC+v>OthJ(BLMq`G4#JYA5C_|sJkT84YP`lGe94I7FK0*X+7fLVmAPd+HkX+y_bWRc$ zcaMn?0#$f5iSX<=5Kf!ATvx=)0N?1qmcovma{GeYNfxt-PGmmu&{TyQZa52nrXR#~ zeqHiC{fT3AVma>Td-)M5aQ#b5=rh9HjjC~zV|gZhJJwsCTD!QRHz zLkT6_hw4pW6^P5i%)-&VDK|U?q6q4>Pp`$!)1%ciQ@kFM%0_Fxu@yh-W%ZoVvAB4# zf9j*qmJ))MD`jwh7(1?-P}Ycy)a3LVWDUjB+i2z_1h&l?AXzeQ6=b&=O_WZT^Dzl? zC$|F{`swFar*3~LG+gYuqs8J97WEA^Q_Xlk3=zc5`|U-HV@3$|@~BO`ApKKo&4SV0 z2H*_T_Gmxrq~}I;pN-;Mt0JIJlPiiuMl4#7v}D|7?u#c_=c{rXK4SHKHaL)6}o+5 zaDnm>kQ{np7AK>vo_4%Rqd2?f>sr*=IqeUvSB^Yu@mn8XvddJp2tEU3z* ze%t@`UMo>$#%phRc}%FWNGtA-U#{fd^cT1(cAjbApPY;CK-)Jd!M|sUJ}X&&8r{qJ zYPXe_Px9+UMMDKypYXN|xRU+^i_B!+t{yImlKQZ)a9;|9hUG3uX2;kDwibQl6sFMb zO0^er|1jtXU!A8bstw${R;ivRRowQDDcRPg^($})nmZ+4Qz?G9suxLM;G%`vCv?oTO}MduGem|Kdk23w#v7#Q8`<^tPE~v)eq`;ohJFgIE?U| zSRd-)Oub^ni(Z;Mgyu)v7nj2`s+Y);I?Q#Yr8O8D*tq5rQyun`4yg~xz3zOtPa{`* zkL}~M%VGDpdjo3%E~S!-rCyL*NDY3GnnCQ7anel=60ia7n^sz94eE#l!bf6-D6O({h<32d_#Vg)L^a*(1+uT^8$6mB zfr27PWgK~)HKlXj;}2k2-9NR)TdY!MjH(NNe-GYDtjt2ATB`RN@$ZqfSPRv|tJ6tw zOp&r%1_*pkaJK@QKsx+zPF1X*!DHXDJ4-uK*8F8i>JUO_RC`#=?UoQP=r8?_fy&?l zhv^1F{~+OqrWsCZ)IGhJ-nw6<>!=wRv(6e2{>@LTUvZWwa{Ds^o>Sz@nt?S!;%J!5 z3zVrt?Qc!ssB%YQH{KLPIpS6~Sl>(Qm$mNFd38bAlqC5S!>EsgGQq(cfb1^hn|I( zLW>$K{n0XqdC3*N3{>Jop0n7*=iDP1!zcKRsOz@QYtxOu`1@v!kNBLVjgy7a!fD!m z3{G&5Wo%on#>}k>ROz9kNGVTkdyx>?FhkhVU3ysa(0Ef~^cW@6Ay z)nI!ZjyS9qj z#gz7C$kn46gS1DDScLO5e|jJz)I}Ops%Ra(K|1=@-qP{phh^_e+o7aULRsH6S?IaS zxlp)y=j#{65%aju)_UKSgJfSB4SpU%Ttm!r?@hdH#%0M&J!%?TMoiU8I}{r73j$O3 zM+^}?SiOg>lQzz0)vuFMPu{;BH+kx)ZYgoi_ z5E}Qq2iLA0OGAYlGb{qbbmZBqhsUwI$B6jUczSoO+`D(V%K;7B6Fy1P45kF0msz%_ zknLSZGblGAid9`n{r3uhj*FJZH+PAa$bSZ_$`B?2%4)elKsUhZ{8O>WrXHbZJn1|6 zoV?(iKuW)aO?ot4u6S#{A(LNRmTv_^l4pF^l8favoc)NRMXj08;KQCScB!CE`0 z(y@WzJo`BRL#BLr_fIeq@VjO=xrVgk>q=8L2)gZ5$U*=}_gz!=MhAfm2nQm=&H>Rt zUF3^rcv$(Yaop4ZdIF(W{WKUTY|x1?x}UX5gJhg!KZq&lr;0V6UkWGc{y^cBi0)_W zSk;Q__De{WNY}k!&E>egw=pD;F|l{5DWUkS_3T{xA!s@;9c(I7Gh7OV^XGsNYg!Oo z!L}N+8s%g{W3SnKRo5_cFz2z;f_cHS6T0~dxY1{#6djzNs2ZCM*u6BcDIRK z)5f!0QLhrZa^hY-`PeP)KAo%6^#?!t9?SK(Yd_)>j=WM@z|+-wGSGW6r`&iES z^pJEx4pJh{1uMwh*Z-A8Rjq%G>{{&>-1~lq9?M^$<&)Ln04)rOEuSnwtB3K%mnxuA z*xkHFB}-gdoe0qPzO9D}hY%lRa2&(1S{*q6PBd^fi<~R~wjMqhv@O2;Tb_3A(^w>S z0JZN0?wy%SE;cG?$?M~@vepoF^XNeWG`%7-y6)RR`j#PzpzKg=gY0566`Qu`T+# zut(Ld1G&qkaEZt+HJEwyiBz$(yGeP^GQ+xQOb>GTCKa>7lw(1g53rx*im9H1xU8*0 zKf>zz!1Zr0H%Lp48fKm)t@H2asxAw1eg#S_r!0*orJ}%5)5F}o)Xi@atpGgUb7|lR zbFI@U8T75{5bRux(mX9#Iu4N%u#>8Cu?*?fbEC1gyqM(ICA8X(|c}YvL5QRz#}xTQyb7_BQ4=$ zPVvQ}L+)=jG4^v4`=d1cNV;{@$xBPVMcE2!%KIT>{MPr+;TFRd%L*4FkNeksA2YWu z4|pE=6p&g*B0=(Nfo!z04yxJh#yCB9a&5-lyTg3<{7-)C>xwIZlz#&so-{o8$Xa8OSE}@u5 zwV0G)5+ibyheMO;rrc#bVAc;>;!(0)IjWYWA3zM_vf<6=d^O-`+|+ty(DEzJ%f>~r z&*8aQhMfY2S>Yc~!y16tsZ8knVW)&@vMDdCjPpibS$mTcpoOfu02-<^cj<4|tTbZz z-|2|FWThZiN=-kJbmsgD+^>v812+@-Q4T>B#{D^SAaS0?RVcm*>?RfPE7>%vEefpi zYSu_hK1DGiTB=~_Tuc0lGPRvW+teNVy>oA(9nc0-^%@_-rbw-Klh6G zU@Sr=!x!{6`fhq2N_@{3sG($J2#@Se@qITYktj|DFB%#P^&53XUhLbyk36ESC))%A z)BNhdo43rgve7H#PsN)&Dca(Fi+3B|x{rJdp>N~jGc>=aOVrGnkVc^NN(-$G{6AzAFZdkD##%n`E;p;zW469DOEO&sr-)z35u)P zG`msP*iG*bhWl<*T^To}4c5mf>&G&sk<s8v zW(r4F1MLiJ=xy^q=3*@8k~U}1$sf^amAP$^B!}9DmiwD~f$8Cj?Um{!hW*;=EaM4f zoYS}ED)SdA8?M;t6*4<~34Slat$kFXLRLtuHKA9^aiss&z)p`_h%k4I?e4%Ow$M+P z)Ad>b>#fM=cLmHsHV&Rsm^ViB)rZAn2hPNOV=56uV4fXRx7}hV9FLApv$Jxsj7Y?mH07-lCt7QYETn%A)CRMCl47O;xGB087 zBzH&O+&5|dS)^wgdKT6~Vx_sHq^|88Q={?mQ;euk3H9X;Fk1#Z1UnGFDtv0+s((bl zVk;It>uZL4A|bZcRZQH3F>AjlesHyG(6xdOabm81y}WWZ6Le(mqDSC#ch+U;1|BL% zRgj1ISBiD8wWPzv#r$Lta7kChL(E$IN(xF6#oXlrFIo9bCnK{BkY9333fbCqGo3n0 zyX~gP5X%{s`$Ip5u%svvNL z+0U@9^^3%5F$d`q&|v!URIQNQs5EGd>hQs%ZP#NWHd)R1RP82x`-c`6l&lB$!$X~B zcl}xHKLC#o;a%ExKpE>906oj7TVSUww`I?q0JHo0n|r59=6kah!qpogcoI-;;ddex z9A}aca?-SQK^udG8}JK4BF1If2n6@<$?5F#LRYY57K@A>pkM_17+iB8+k&YHg{YtjG0u+0_f-^{NPN%siMYUyo3AY@ z@^6vtw!Eb#B|XL@&MYincLbK<;t=_b8SEX!Cm3YxoNS#@l3bGyho!{mk}m(+7X5xO z)56c&IX1ZGJgvqEcIU4H~N-)mXX1MCkrKg`w9~0{#YADSE%JM6vdPhpaISSI(zG4#@1^0 zSq&-*vZPnG{}+4j9aL4;ZI23)1Qe8ls@^}{UDR&adxg2?8gtAsLc4GFJ}>sC z!CYLpcUExCy)}|82%aU$%l=SApWxJ^RA8#WaP4wV#p({y`w^C3=kp!por-V!knXE@ zdQGFNM?#(V54*>om3cXz4CPG=4>U_#9Gj(i`U%BFitGn*V?2phJN~Lvll}E9Z&i*c zeSrv>2MZp|otl1SUQfbqBKgK`N;!S*xNnFV%k>MrUJ2|Qg zk5&f`dvUNmp0BbYNEQ{%b6f4{lA%g3<-UUZUX;LBG!75?6- z75?;>)8Bk`BWXAR66aj3uMdI5*9dst2Bc=rO~Fr@b?TgRa_6*bU4wwe+atQU^hJ+l zAEobAVRx<{U#V`Ph{DC$t*FJL)RY(zt6KArs#Ux7ggHwB6;P0;6z@_>z|fGt#>UkT zaHwR{RCzwH*&xML@9oqz$E2JauU*A>8Zmd?*=8I+Lw7dehd+Bfj$fuZ6q+M)+9&0@ z+RpsIPb=Ib>xhJl$7y}5JbS(At0v1TYIMy-m!A0R1fizVBuOIogu`)6tu3Y8K@t^q z)vo!Zvska_Q@xWd_^7VQot?T4w#hU94$u(@GkeeZ+Az4Rpw|dst!{nZoA31Qe6)T) z60Iuk063Ln#Wl-*xvF({s?OWpzMc*pzmItP?c3qI<*~B~a*L)NWxguU${?nJ(_wA( z$;sGbTe2Y;6AQSb{60r2-nvh2X3l6@e=mvlp6Igd2-_X$wN$fo-)L_6G;-eVGJP!6 z<yOKQ4B*oqk?<8y~V_f$UG$YWDT=^lGX) z4&01Cvvd<~Y3oaTm7krgXtErt02Rg&z+SfMh-a@5@!T5*x_j2QxT=6@=P@w&d=CnA zw~1u10;|{#@>x1n?F#C(uw>phWS;}~vqM}G-HMmPJ;XN``QPBhFFOz!1>LV0^GWZh z-CFX@Ncj&NAxIApe2jeVL*p98f#f@i{df016OdLtTpBbhclDl_6(ci+r|M!#%g5a+ zeT?hICBLBDG<@roUNiMTD&RDz7uYlc-u!YEH*>zOuI^5b5MR9%T-DB7=F_(BcpRWz zY6C&^_drh11qh{SfmV)`OGvGYk9U`rmuL_28CJB)4~61CX7~E;U`-|$yyqH7QyD5D z(LQr$(EoyDB_f%%h7c58m9Je3l|kpMOFGp&XBQ`X0v{{|Wqz=9?qz|Hv@^KZOl6j(1fl=jRtcZJ)tnmC>gpG@To@0q=3w!jeoE`kFUIQc*^%Fqb zjSb0~$!bccnq4A3@Xn!^ofIKqdBpjEhARA;lVqsc7-xU+_Ax&0?O!;AIPt{wPu&Db zGSn*2NETVlZSR)VQGQc7F1#*%8rP<*>Kfp2Il_)X=8YS@t!*hxmw+-b)4X^_eKD$i zZ>^K0wu9v1qK9gIz9(v{)fLwKITJ6Mi3Tq`C(|g)2x-*p%HjGe^9+ZvkeGg)bBFVe zac0ni{0F6R-qrl)ra?C)Dcc`6H7y;STGpMev;$!q;~TL7zf3xAK+I!G^)kIC1~v4R z7kiVwzMmG$J>B|KWf%D^b^v!MG>5jS{n5LTuOoS&4IPIO$o&7yw_C+Q4s8!A|49bo zW@8Qa83qrPMUvTWp5n{pF;dkPo3>QkcRT?C!eS6>Q`AwG_Y=xI`}u?i#*wktH!`1q7Jna{IqeSuIiysrA9P%lV70C&oKE&WidnauUoTzmHM+!_Y?d&_+aOXzj%{#^f6pFH>#4 zq_Gp1Yj_|=qx13B2r&+0^e;#jdgk|jT>@c?KwO$BDjm;vnxE2sN=q%^RmItil|E*B z>DKn+<588iRa1Q3alyswu@%1$tvrx^FAoZjoM3sQP8K*^heu=gZ1>Z)1g`jzIjFe; ztyBxk2bHsAuJ{CRbp|FtS;CbDCll~@{{_v`#|o?NhhHZUp}ACazL=vjpHbqXkzWOR z8l3YURrql;RlCDSh=sg{9;uXp4se&T5T;z(tkb>8$*0tME$=`X9`NNV9|>1FED4*a zIW0RQtPlLH0O9qg9r%Cpb={GyF9CVg0nG{Q)c3Q^y4EKj4qZ%osPgYezvcq~ugm$y z!s?rx76FD?NUc@drY;>lic^(TI{LNr_?LW$wl=y(Yr5W}y-)&E5}370=5ow-UhQqU zB8q(3@&1jIoyk)*`dEzL2k7onIp={NlkUct#Qf*4?&W~(G*+GFeIx|Qo#d~rOE1@z z9Me*n+~X4%T>5HjTpDL1Us~Y*jwId3wo5z36cm%o{qE8h1G-h^O6)-Tsnx5zhoyt7 z-#*P5FDab4ebnvU#)>zz2SDD9mL%x2;lJ!rab|%JfD*_zwPx6z@`8Py+*Z|1t9qKs z6Cn3ipe9Ma$nd&CRKpnLS&j4gC&FDjZivSIoN?c8U^nESPX${6j%Q!zU7Wf6-&f58 z4`~k1Nr&9!GfvCJy_)&9lngi1mrkrFos@~h!9xYMX0DZPh3+vCbT9(Rkl&~KBx$ov z#?#^iyBvg~+U*CZZy%PGJx^C7t^0!Iy%!h)0EhY)sxr>?0F~Fj(TuML5Xyb{^?kq( zBtuAlTT>@}Uy`;TuR7f|JLBnNmrltLMA`ss`ioymK}PiG$> zwroW%`(A1!pYUk^+_m96EG#}mai zH8v%TRQm@I5B-#^?qe10T{`#fKSw7>GqCa%>4duYmjpHhD;C#mV))#~b83^!>yIVQd}NPX~)#R@uR7`g6iOL1S)d zVfC!Pb=@Jek@eVaZVmsQ2t*9}bHe`o?*GQBlJm*`wwJ}GQ!zTAzL6ZsH8@{*R^Gf^ zS3akGw)zj-rBEmcFl|6f=C=AOwEhRb_4t;><(8MRc#i-0r{_T=)sDU)Z4F{66iNEt zF#qo@BFp-50&PI=9R_0BU`&vj9BjfA~}o)qX#q{u^NqY_XQmieZ2mengM*`58Eml>zC#Rx!1v{h!vgw+)RI z)Dt(-QU3D-y3Fb{AhLK$L_Fxu_+yjhnWdkpBkw;*{%D*B)Fq46efLTq{qMy#h&mwBJwO2wIgMr4GgFa*x`8#1Dfr|ePUh#|0+O5$)ZhuN$#vmafyIMGP$j?nZ?F8{ z31fc@H1i>^$C&3&3jJb^tv8scvgy#t{K-^;Zw$(HAQb&^KClPTccqd06KDQE>_@5E z%kfh$F}46Y_{q@t8mm4mw69EcU&H)!yTzU)ooqUIdVST|2L&lSd4_wWE>Z;F86PX;E-t+p%59hM3H>6NO${rf$rM_Zk}V~19F z*&b-4{lK@NwZClpPdnmqkLc;o^vbbK9r^?~Q8rNT90V2#e|`Ye17xfWTFV&geht9T zm`m>kfIcU12K;hf$@%Qkon#CYjMmQ=3{OL+6EGMnHi{5xyIu1-{-4h6IGb;?CCq$Y zhr!U;^HjC0%#B(%eAE5&L;o*B-P^QAAlx)u)pHJ#4Cu5xFL4#sdD<^FGW8FOs*vhv z(ges%TR{T$&}k{N|K{;I4kYLEPlL0&(mx5>beCife#X(I9-ne>Y0+GES^YC(`mc|N z|Kc>^J^9E9sGuxXy+?&V=hbGxc5rTKg3qp%;m_fTJ%JK7?epgK^25A3uz|cS!R=ra zSlu3U|1a&(-KEb2Kf8K?-!GI(3Q|XA5&Mp zC1d?}0)DK-gO75&mg5CA|FnVri(KoUQ?t2zb?f6^Q}#(45a#EFCY38D?CYQwuH@1u zU;~N)d#Ug)-9vZgP-~x(d3mT6VqI7)e`GV1#=CRV<-tOp_rkFSI7!Dh^{N)Np)HZ} z`!%A1lGDR~pkV0B#F0TX^c%I#Un!m&Kes-Zah*Ke{6>7KsPKpVa~j`1c)7zUL2bwP z$51<*(85V*{`kjKE^lGJ^|KCOxjO=GK4Y%6>BcHhxdghs{?lLc0HJuudG;fus@-!5 zToOW4$BtO@wCjqgJo;@DPi`d==PL>IQ}PJ5$JrisyC$Z5K}N=Dg5J{=)Y)Aq=W|g1 zEvKDW0!@@ZmAU~Oup%VJgq%7BRjHMPS>+PoX|$&ct7|t=b*lV)rBHX$`FKMc#;aje0uSU$~LX^AA^>4G2#u|2)G zMmrDq8F6hrl$(80EM8N71_m9Uib<)eu-78s7Cx$W-*S%_)rs(C7NZ^V#yc^G?p@bET~ z6z-ej@y%x>x4kmJxfAtMd&0r+OIA;{4K^wKNorx$#NgV&fNLUsA4fLS!*>P19ij+9jJ*lO`oMD6X+bc=vz?6mv*WVZLB&`jd_ZR3r!5 zZrXQL+fSSHi-36x_^CR$(JQ+gz8b1xjTf!BQXVc)q!ges|2q&QlP7jOa(k_>3G?%6 z_p&iKWAJpoJAhlz=nJyR5AOz^R%%^_G(SJ-3?rje-_faekW^Bi)FaAa4hpAn9bq6x z`v!G4u<(0$j5=C_zR2U-!G!HJzYSCfqKY&HbP^7UWXYD!^8quYasbdIuH{^Je1h^1 zhf=K7jFP$cR)@GQ`_CC9$GaHRxt!BzML-h

ykhHGPka|77@>+vwm2fBwW7g4Q_H&dazd0Os;;x$4W0)*Kh_NuiZMPBm*F zd0lSYPaA)|2w*H$ASCN>Duml)&P1#V>8`!Jx3ub8I;%Y_KP%Q6Z9{M<%S8#rjSe4X zz3Kp$WuRfr{ea?*cSDkH`APqJihZ$53pLWOPRc5g!#bDy!=+MdIeP10VFmjnV`w4KibyaKUfT< z^LdWAK=%fywH9izg2Jt?UCsGfAVeh91g#gN`4y99JvD-DIo(>)s{#DbHICa$k6Nh9 z=F_s_r;>$m7o}kN_W;jzv73A6(!lsw3+QU=NS`GZcYamx((J|z^Ubg1{T2Zv6slPp6j2|(x!`-u;x-PrWU^@F>1*lf5ECzb^K%xg%Sp+1b{L4p`;;~!d}lM|4_w?sq}dx5*N zIa9gdxa;Yk@7IP@c~)cGc5SrQ+cS>WZb}?<6O+6LTGh2JX8PYsOhUPD0ci@kl;3Vr zpXL9h7UIKQiUO1`4tV>cq5|DdGLiQO502OC@`0^3bOlrSEmHvq=wE2l`M<@vzq9DW z-_f`K+2hb5Sx~!Y8Y?~kC|Bi*FM%&@kD%Vz0MM^{ypUH=`dT{FWEA-ZXa-O2W>xnO zw>f&Pt1Knx^2G6IAp!_m* zJRL1(gGmSCx&W=sW7>4@#kEiCF2FAFKJ}lvFCTXYwewZ8yy)d6WrbSP z;xA3R>Xf`zN)?nI!g0U+FHyCh$hB;=o9Ow8qjs&AdpVMR9Y~3V0==BfHOjolg?l2m zHG6@$>TAn@YTyU?Yr+9iNoI``pbl0JSIhaH_){b;t{>Rd{qay|@|_+?wg76d06p0Y zNpf+liyr{9;>UmSe45Cp_k!on55uf`k=?wy!1B1;O{47TBd3nVUqsvfwge<*6-LaI z4e5m{wb9Ueu5bc@8jC+(0Wyat{xx+0q%D6;7^a-e&qr}T$Zi7Jo+`tc+LJB$J7bz2 zKU;3SL4Ti(X85=s;UQ>4UykTc6Y+elc5(>BsLX7uH-nbRJ^?lKA75kJ0SV-+QrCNT zU=I}ezX6pX+Ehe})nx5Buo*M~-Ax`&a%X5ihbDkXq~Zj~40~EEeT`i|f%JD4&ViO# zFRw8Hcy*Hhc%RG*AAo)$q`Z|ZqL9XI%5Ma<5E^RB?IzQ(TYHn3=A`FUv|Hb>07daP$JmH|YR zNvC6A^H<%VE?Sntw^K%o!H(=60 zQF{dpZaFHPY82QQ(4}q@;C>KtUivzT$8O*qhQ zj)pdCuh$Mz$ODrr+f!P|teDrL?{kFMncFegOI{VrWxo2>TZ1&8e6H4Yx%FvRR1_Sz zA9KO`j&->HvJhwt0Z!ky-r+srw|09Uyy;#~KS_+)f6A)uUYhDeMGYSYjei zCFt~KImv$D(c=+mGF@Xau#uf)9d~aA5zyIKkCrN#?M+@7{`J#3u#VrZ_C1e?csqe>pelPwCr#HZKVQQn z;gxw9_1S;;Nf@Oz&#JHJ`YbJVkbB4N_1aJC4wFN>pPr43z|G>u-F>!&dk%kOxy?$a z^=Snpa&iZ%+>@8LV+9?Q3SAGNtiA^TFPsor6eZ`$x(O-1U^K3^vEqy zcEL0*FNWSR&gO{pB2|)zZ-fJlTFsC#rVnwvLpo{*$pIvE1uxh*0Fa z#PYsKva@~oNhn(*XA3nEP-&+EhCtVzuYHY*p+E2B?g{IV?H8U7Aes?v+ev`JIJc@O zIKqm6z2LoVV_>v!rS4>oy$Ps`QkIW7bQGOzb==E(mdjkP77zNW1#K=OE^uc7XT8la z4qBYO6sbrM0G$f9^|Uj&}LN90$0Q*Ac-9&Lz`%jc{2KJOb-2)o&_ z4t)f#H(PfvoRY+63y~hc7^iWAZ|nOvdur-QU~7GK2+jph10Un|K9sFog+*tRc1xpXp|H}()p%^>Wll?3fnMDZy4|kd&`fwNI?WVpqXnZ8-X4r zSr?`hJ7x)539R``=3S!-Dlz8JbBscZEmw4HvIt43ThfRp zM~g;wvYP11Gld`Lllt8oNnIxXm<=k%RRl%>g}t$J>Mpjx*LD zMs_I&kKyj~+|znR3_pHTOc=TZ->5Ma#uN`~W_=|R|3UY2>ucFe9=H@GkpiwyQziTK^}FgPrdytg`rS>$inx#Pel8Mo)mQ~w zIVQJj%Cb_pjh8&y3NqHEqGkO;>Irz~@G%;UIlid*iDF~m7z>JX!7CrM?)%mQxxGrT zW#r|3IIb{DTo;EWm?po-NUX)fII=>hVuw9H;XAyOc(D!X29!RHP?Gy=<3<7)DDi9O zu)JqnLGyB=-@YN~-JXOoTeQ&;Ep%!a;UGJSJF(l@lAc@oy_K4L8O!F-O!8PE?yaN? z-f=ch&PS^9YS~S2`k?mhuN=;1>*E|xRc>R+uzmSE)G%hBOc-pLHQyy&GkdAWpdF(s ztB5-=(T60Amg_|_ClYfQ)IU22@SjQ&PoYmoy})RfhGCvwzklA+n$dI78}>u79uaW^ z@!G5>t@w^qT(WJgI~U@{D@(%f{VUP*iHi@e!X&uhgk21>$2XU6;058Gvd73u=;K60 zPh7Gpy^pcCYN3j>BI=BOJu6`hi^7zg#8JTIf+an-!tsz|t=?$d1Ul%MUeC{{Eyn0T zR#2(muAjtUtBOx2DqKsD_4bFx)$JkBnd}h-3%qaCXiKzD>)u460ll zA^D0y5%=m_V#SwXvJxX0e!_`YPcje_$}$(fE8?OXm?G(g{I+oY7e7NT7Ph3fIN{9t z8R?%Ju<59i^>V^4pxY&xnR3I2Vcx`B^XSJJoW^_zFdn|8ig9zzdr6+{eS{tuZVl5cnNa^|Ii>l z?4_I{u4x%PeXf`!shkprRE(@2T+$tFJ-gUAj!e((`fX*H^pb4DA+d?PfzF3mEUo-B zVq@9w`(2wk^RLBI*+gy?fV~2uSUqdT?R~(mO#W~=M}MyB3pK(*mXner`Wm`9F)hSmFYR9^g9RSg^pSt>h}J}6;SeSxzZk!J zwC>0cPI3r;gM*CcS6*T@fpMf1daCx?kJAqLUrJ>el?|we-oeLc%jbnN3&@7EzU9nz zXIf{}m|qlAEN2fK@=I`?gFpm?4M!b}3s~j2O)k!q>ZB@MAgpso;i|$b zCw$FecB7ByXUD-Lk99aB#By4Iy#_D*F8cGpA?CWaMh!z94i{?nQiQ=xdm;_?zq5yc z;0q_U^U{e7=L?)?p?bLwIZta9FM~6a`mdCtABH(Xm~ico&Ia8&ZDPT2{GocZ0aYw^ z#)_qd`?o8;TkFCr$*Uzkq=RMxzNV4v)=X?hH0TFT_^d6$4PFgDTK8No=qZnyo}Tz5 zKi_rNSCbokLVe&$I?>@1df%wob88`)$#X?9KR7dBv;LuVn4%i;^!14|=APPz>Xg}h z%)h7cx>`(FyQue()T|gw$!)lNCp*(Jp-~N+PaY5ap}@~Io|vQfGU7@Xb(>@cljPp~ za|bNB`^-knxFu8+D8EjkB!`%6F1CN2knJS!(^_|cg2<|$s-GRrzB9b@y?+}0; zltvs&{lzOrH56D~Hp3O*sTsY-KRmQU5!Q4uJ(O-T!;rnqM$ikX^*?qPIBEU@ukpz+|lWH-UEt z?R4dA1RhW_cVuO=csd{Rw7%&%jj`N(P_^5$gJu zr{=2fLG(5RvgQ`5z6VWoa_P6OF5+v3J|%ih?%d}mAr*nfWddn~1r z{6-$o0)Pcd>{}?*Op~q4-J0&LM*>fTK#(gkI;~HLPe&D|tDCgaEL4Le>4mx|K z3nMAGb3O#Vz5B1T5H}ij0J7c2W-@(h#SlzV4SH(dlTE|VFRt3Fzfu-Gyg7j!w`;l# z<-aenP~hODIezjm*;qBIc{9@YB+F`Z$E#{Frypq^c($`gHvNXE2VeJ7*HyI~@c(|_ z_>NEx0w!~xdoEno4#uar#y9TNZ?69SV|UPWLoO;{lkPOv&eJ;ESal58UIq?TGHz1L zaA(L~?<3!+`Rv*Va8Nn0D_lXbQ#^w1jecOe-1|E@eL*aa!pLcYC0kufPpZJc zLa|khU6bd)F|Pxc&^{LHNSO5Ti)#d2%#~?CtX#rkCn>0>-g!uu3{rjeSTE9cb8dVb zIBNZKk(2&%01~!sfjmKZ`gF&l7^=<6%Lhj@MDVSmD8xLf8K zC{3!#6GkIc&f~y#H{=VHP=S@UXSZAAi3d_GXlt^zAuEAzj1l+3Q;Yg%Xdqq={Jmod z+x$2sa(B*7kK;uwu}^Q2>ew{^#9Qd|vocC^)ra~OW5>onzP@#=zHa;Oa~7O~cRtN5 z?Tc%CP17>bxn||*+gBh28Oy>j=Z~(*vp(RBHU#baS}cEMg1FJtJFkC?eRKpFCAOTr zRu5!D-~tR*-MIIG;AVVWIa?C(09k*SYSs2vHD#cOvFmj>7hfDH+mn8qF3s~at8rC1 zAMB=^9qH#M3mc*OC$Dv#zDQsP0%M564+}Ye#S~RIm=*!%5rcQV(7idEF+VtW4LWU7 z77Z)LT|)0TTC>SL_|}NjFbQ{VEI7UL5L3(a@YO6)+u+XY*1LO`hu(Hrl?ICntv&)D zG$2^R*9*o>7J~Tn4*-@oWb+g{V$u|GX_-%eS~DAQscWxx*!kmETVR_68AS-d#@rWD zvl&+j!p8;DmBmg!j5tnD?ArPsYwPUmpC3K8czg5Uy%)&DOw1lvU<0E7L)LAE%r!>VYnr8!T)ZEKYl>}Q*~QhtYW+mDlV`g#(=mSJp`U4r zMGkbeZP65J5A3P$y+=orb9^>mt+sGGa5P=3OXmpR99*w!z}c}hfShtY0=<&q1jx!s z21hQ72!Z(*{Xk)06EzL??PY*=DK6^HZO(+UqbTYk_-9`9#gzMDKlMs4F$VZv!9e4X4Ws7gaC`}|Av+L}S@V>2Nfp=&G_|R4$mM`= ziD$y$@$q5$*-mb;)W>KA7`XaVC*UWbG2Dv)v0B7SU?YnI{PjR!($Yc~SUw1{#W5JH z8AN3YncA(iTVK+S=}3K}wA5TvgJaTDT_*%si@w~Lu5CHjfaWN1LH{ktiJZg1UNl3@ zfEA0^uPo+0?73dkB(RXeEjxCx?}8_U;Dmp z06GsbEEFdpR1^>NcDWSx1mM80={N90(^}txb&QYk!E8%y^8Ld zWPtD!FC7N==dvBS<+pLNo1j913d2sC?nt*{Gx-I&|naY?wo+&!p>$* zQTu}9ig}egu)9S0KE9|3-g>jw_tN&h2EA2rGpWhx8@sOH%T%O_1x8r-__Jb1%F}zf z>R|Dzu7eyk;;HHdnPv*Jl&ij$>)=@K>!X_x0$!NF9)js}OcXFIWLg2P&(jrkr`9Qr zqCoT=cxMRb91*=KsF?65E*u6p3~#fV^BS)WI6TZ@MT(Sm=??91M2-ZLhA2?FoIQoN zd<90MMZhkEZ$vD7_A@fW=~XA8oJMP7>s@zjliNEy^vO3YRf{g8Z)Zga-m6HCZbd8@)4NmSXKzTQPa^2qnsh>IIz%JbsW2RGi@hp?UTb8_Pe07B7c*? z_yeuSk4!@V@Dq&Me6p^#bq6kCvy(jlt?APetM}o@iU{O1J~rkwrlagjHv-u0%Mk{4 z0LKoS#OppG_?Sb>N}5RAIdM;ueJB-n2qw^Z7*w8&#>5>BYmc9i`_F~3YYG5_*Ma|g z)Lod#{KgT;gRk}k+W!Cw{9~j9pRUEytV1bID?=ncd)Z=0X@;M}w8nG)%8;(>IPre% z4(nl;tq+mDa!WfeE0fYKGH7F-a71t23m-aMNS|EdsRM^|06@Q3e!>FsRa($70CJ++ z)NTit>?u`!#I=@H9LFE)*f$p)#K;FT>3e*#8@0X;g?v|#-rnPbPx<5Beos{p0N@}&h*Le{Utfk>xslv)*l|=(_doc#PiuJO>aJyM?ZA3l`uki?~mV6 z@{QcA=K~P_`7qOy#q9Wq2G0GQy5sTnnI@t${mmmVz@*PxZUB7a5Hf9`xoG0w$vQT9 z?HNK^qQ1>rVh{=Wx;0ATu@RGMTNRUkf1*yz^AyOx2w$Y4LBbIl^UZP(9kf}u^H>7ublei=NQ~qtV`Np zoZFcFe$P^8>7V7=-sQT^aiR6;)NmzVicpTU01R^|fj-rKTCj+%6ClpR*L|)GgEIC< z2#|z8!%abhVFMhnxb3<0ykuf58js<;rlW0drYhC7t;;lSH@fwD`fuOJ3M!th;<7PI z_jUmY;{tePW?JmTaWB~67-s|k43%}58r(TFFO1e>%usG?&L44=FP3&TX?OBQkZ?aY znj@#sHsyIA_aIaDy6Oe}BM2`#i42_$XBib}~7U1OSjb(3Ps0!yqL%G+*NKhbcTZSp0vsbGUHqEMJxYK38<(3HQsqo09e zqQyjbV8Y<}<)28J3&tqgAmf+M#`o(w+K}{7S@9ZG>`2!O5=^7_6E9*EtOO@EsPbWr zg1k7`$VeGK!inysJr{tA%lV}R*OeQ@xWnHA6p@p;$JEn~72_L5$^Mw5a&;lNm1AM$ zTqrc#mo7&q_|CzOqlbp@-^D2^tlnyu4Z@%x+L52)T|@ZIBQU-R&nb_Phh3&1NVv0u zAsZ!9U#a4ej7nm~4a2R~CTBPBB^M&6GtNR#n z+px*yqFI@vLx&QIz5}l;VAZzBe)W1WD$v(R*y`h4+@>Q!0T&hJ5XlN4)gc;&5YGAa zFvi)AvhUSx-(@u^6I94856@u2PEB8@l_L^oJ8RkfWCJw=6Ca1?q=M6}t3IB};t5i8 zQ!17Hvd{3r)fteCe(-v*J=gj0(EuMaeIl{fG*rbf38llID3t9j`2pYjQ99d5TH}hJ zT6d1Wk%fxqM|ZD%FIpXv!RJb*TFzcS5 z_-udWzf^jG!G9|J>s~C{1&j=gJW$nPWjnk|`=p2sUB-XdSk*2)D)@|qoDu+#hWNDb z%nUOr(RwU@mk378rdJ8X7>DGnZ@*tq%}~71=@Y7ei>|{Z!>^BzmR7_dr$U}({O%^g zKX(UibW>s-tMh6(g8l`H{`&o#u;J^#CpS$o>~3o&j0A9kJikG3 zD13J2EJcr2HdcxQi<~yaj0?`ZZQdo~=?KG2Co6eS0;+Hfn@7fC3;^rm4l5yU52}ps zq+Pdfp&=8)BNq)*W*KU^UyK?8 zo3xg#i6i)@cQy`w+{x3Li5|$X^wkEJ{{wux(uQ;-10Q4G4QZ)&(A5tlXc=yx02^wt zEE~JFb$rmFf9CKqW8-MK5O`3zpdeH-Htqz+6l*_NxOM818yEaXR}?nGv)m2i$t|ZO z`Zx;yElr$y`>l*Hh0AZgBI%j4bJ6C=$Qi~e`i9W@{hdKw3=30)9p{MvUy{@lToniL zdR=2x!pep9K+a1gFibyQ)Wwb;*ChzM_&&CDClSLhEKD0rAnWa>tHB17!6v|`u;of_ z(`&m?1&ge^@{YcLe|S*GO?=flX_ z&E{tv@~e-}I!eE7G&hpzs8tEZ=cOD&1-Nr%~^q`ZlOhAeJEB-@?}cCO{ZKq$v9!iiw^)2XTbE=hoqa+-z7uDEGNYw-fMO?kC2MjIB>zHd2eIh)wcRE;0 z6+k^{2-g2hT+lcD6o3)U7sL{Y$Bw!7j2%?`#VKs`7JWn#i802?xZtg|Q>6_bAH?;J zZNd<*nYXiAkyA(Z)|Gn+1dG%mG_7Y~7DgLCJhg^lUe*;@n~x~V2UkoBjx^utY&SK# z$x=Gf37$8op|XmT+Y?q_dbOpH5bhgcuDbCJ03J^ku`ISmv^>MGx#(MKTd`K_708Xz z2?L18L8MN*X3S`Oo#^@G51=+8QY+K1*m*IBudA`vqBXo%{L2+J5HMjJc-SK4tt$7u z3FvKAIc^&>eW~Wcli&`gVBv%hlQCk2$qS}`1{oqr_%mZwgJHs9wY{hw^UQ|<>v15= z_!xUeF~)TBHt-wMwSIjrD^Y&2MchT|sb~_TXZ2hHaSBT*kpoTQDFfazsNg)?Y`T!; zXG+?MgU`nGkb{2sPD}bkd~2k&b{0T!41U6oSKsnN6PiRUuA(p%{2)3t+bPt|-e8=PQ;&!fGx%%L+&@(=^^EeXKW8~Y z@ZO7-l~7T#MbF`rRuD=81&|$YP;T0mgW=7iHL#3+ce7}`4C(_oYw*kT9Nm;$)#X$%YU{ufuq0E*jNya@CktMU-*Cnc1!jF}-?J)P+zI zgj4Euu0@y7^Xu(3;B$p>$0p0#gA^6D{304rzp)64-X~rT)NdoPhEh1Qh;Q-+o3LWz zlM}`pQQNO3Vg?#@b+0uP$Mi~$c)I9Y1LXAn^UR+`P$Vdi|GYxMFwp2t=wgX(;>>W; zGCw~6a05+2<;+Ws83`Ch4T!ppf78Fr54f#xtHNr4e$BXz!z)5Hx}C zn~CjdK4zU(533QX(wjk`9#uCAwwK%FPQcod(sMIG{`v zTNG1Vf7pi&v4c2`jHd(1B1RQ+?t?ylRER3+(cLfm7^Qy2W_;Jm8}g|7qruBYGJCk`EQ7QB=5GXiP7cgbn-mRUugUOEWfLrddbrZ>?Ol!) zx5uYuIc4Klr+n?ubr_ZtmIM{E~QUh8Q8_8$)r&^ufO4~(XEOu5$jg!q`l2cm=X$LjN&SO;Ym?>}glHYwcYbr!8 zlz_JL;C=_E+7FBR;teTLx&xzbjw|pe#^nIc1{H%9X0z+Zeto1|a?C7KydF!A{s8#U}tpY;&e@G%$5=BWGc z_gBW)gT#4#b|P~3klHX{<74BSCu96q!YUqKX*9dY%|Juv&0eC3x1%yE{;9d*LE0dsU9&gB?war&gN5 z&i&5H$mJxutdmVrUB`(IOZOzIeJ8K#JDy{U{3RX3N?P4}C50vyUB%^$AbGnCm}U^t zsg(uLun}a`QLrgeIA1xNKwMlg5oeA}DQjXFpk+MdKMOZfPXV6Phm3mbH=n^XqGMaL z`@|i665d%Y`4KIfR3Q=`9{T&11&o$NO6Ej*OMhBiiyUH8>C8n_7ZkCD!oLlkg=*_p zN%t0jPLU;xa-}j)vhdW!qVD~^ivOFE0$ns~kA<`q6W zm^B2ng~;ts3%PNYwm&+%oSYVg6VVIbzx3feEX+yTk73EUp31YOsJ15MMt_lm$(A9XmE*pix2qk6mUWQ)AAOK|!9G_coU zVY3$Ephz%E-8M`rns)=Tl@RzQ1m3mo9MB# zk;oeIy~F0KnG4GCc%|OwzBTgkBa%Zlj#6x;C+*WAWRthN3ZH7yG$0K;APONTH3ZZo zn#6^KQ$DD$8Go&=@4dSL*idnUq|tkl|2f8UcgZ$y>sEcXPX_F#CI#*;9$DbpXrzO( zOciv-HA}IVL2SRMkSbHeEukLNFbXdM1g=1_^TVF(?B;5~oV6F}#)H7v=@6zg=9;66 zon^H{dY+0}*r@<+$$l)Ilry1-%XM>4=pcb(XlxsGz97%K+h5e7haI$yrArqiCMYN@ z=wL-IFn_v%3O>K(RrgeL*G4t!da!_mnoR9Nytd6pyVmQ$0pQ<^)quY;&F*_B&tsFz z_gqP;{aq9((DXHzNQ+z zfw)mqm`ydkvKKmN0`XLj6AmS?cYtpe%0v;sa8AM}A!yO#d~@_-hi%F;DS&D(?1+F# z%eP=14ry=GCM4}9dFs2I<_xyg#htOSsrA5`iP)=Y_`X>suZsnAst7>VZ&gW85i*M zsa+>$OTc42cN5&ZXm^8_OS=V^0~Gm2ZtA#A2O0u9)1OdeIsg>E8P6VpVom@A{#e!Q z4svcAk6Kq;hM>eTGygNH>h5FqPb(!GfKd2(m!CGRUT*tqo~*=r2%G0Rx#{Xxft7FT z^&2}K>!by_IeNQKRX5IE0X6T%u!4z+KFTf8IL?bjI9%67b!#$MqbxYM10P-99VUprNXcUjAo7j3Y`F#og zIjXvYW_Fl~paF4_sBepK2J!QH%Bv~}=>``L+F=(!t$!k}Ck3EuB}(@a>!-!Cj#&O4 zVHkU5Ewr8iv?3m#t(g%1LjtZPe8X5R-TXzi5oAWs+}8{{6F4`WCwlleiO3nsySUCE zI=M2}H4ZrrYjU!76@I0qCQVm>_u~Rec*HVVP|Lf#0!n=&&mGdA+{VPH0z9LH@~$It zT56_c!}%iXy}(06()Sv`@y!IJs?Ae!DGR#yk$#-{O}yg(%9=5Ie?RYii5zvIG^y^5 z_qBsZic2e@g={CZc|m%f`^!b^4flM{6O(wU9lk!}m`^Rl9a78hPbCPyRh=WtQc$I& zVGu&n^pd5J^t^{R8=}eWynQFSLo7G>mb`5ToJdEY;QDtCGuNLY>vxsYe&%yguMAc5 z&?SF;uoey|xt*eF>bD?z#2BCj+mAp9IehyWK6(}EF5vntk%4XpyK(2CX4Wu(4d3C* zHug^2h!*jC(9rLL?#9KCKoYP;guVkYGOz}IK$vXHeTGgz&2F|XS_izEn-CDliHCe) zrHq?o=-@+5c8n2`$a=ApP;fl=8My3pVo6SQbK0!|g}0X!L=cFmL!fqJw>d)?t3P1w z+U&zuv~ zUJNa;mwz1_wvTxGRZn>LtJ>zLJy5T4KUm5ul#`c6PW-Y1fbN=2+CCr_%g!tcO7JUB zTs1|z%m@gFr1VoJ0uoOC_~?{HR|BpdI2hr#A;pmtOc(u`TeKkIMy#Ap_S2QpD$4C45L^IUvx2JjeGqLY6j>kHQ zI@O*4*oxm&)F|Z+mUR2W%I`7qGw$4Jv8CdJ$SECF7wp;32PG-<&hWc4psEx;Dh($& z22npTwoBaNk|r$WPBuNOHYo4FO!y5p44gRjs^b7-Qe0IAJDWa*X%_WS<#v+;mn!q4 zwj^TRPcGp#vcod9UyZdG6Ny1M^5$u4AE>mSo!PZuNBH{?eOmQa`N1{1GKoDzKw6O1 z4zQY5R+cIhTS(%IgKp@V^JU|7!!T3sF{$4oh_T|!9H|Ts5a$%R@NkSlrT6%Na)bm! zSF-@r!4d++>4OE(+K?Fm(}UW!;T_j@obNZBzPQTpL|qbe>+URaw_#kc*;tIMw@kn` zW>pB6m4IQ(;F=H!Q!LaNo7)M4(5K6Ty9L7}97B{rCCATU!61zgHT5r|<<3O%ti6|& zSj1={z&Jtbl%}v=I?@*BB2GAqWhE&01QET($VfMgLQYb{41h{6Iyl@*-j0r3Ll~XdQQO9`WOI`~XLG;nTt|)W;4`G<_269~1+_3AT z8qo^D578wTvF1oMeU3*bQB`JoV#h0`vn3z|*O&INUc|zGAwgI8fKSo_djzvO{fuOU z=>TJFCuE8j|B{?S&LEN=hskc?pjGn6_$OD^%t}BCp0xx}8{(M}{ST($?~6BOq;5@` zw5z~zV#olqHKj>80;3Tg1{WA_7(d?70x;hC zeG}dksv$mhR6sFUE>_7}E{D+(rmAD7t=ooinnHm_$^t@R=Rf{WduJUL<@f!2N;(Cl zTaXcyp}SN{2^|cO4hIobLX=Jc#i1OeQwIA!I72_6%i?=luqw{@DqN2>;8Gy zx_7Pnoj+MTvz~d*Is5GM-mmw5G{U|=`q|fQKwE3QreUO%al239pJZDs^QpcYB#Nyz z>?~=$^>H>h8>Q53O;PQ3Y}SDg)NHYX3~FkcWXK@0&re1xm*l%UkLr)Sufem${=|DQ zh@xbijMX}^9kqEd|F@keS*4FZV$XZACzvAK;1eM$lTu4G=g2PnxkqeFKt?F}FzC9Q zmq5}YCTE9UaosU^cLGbEERz30IGK&(7=Za+76_weh{d1-)(vQ}#`>Uh8F!TkOA=|y zVTYf}&eoSw;(bd{+#X1bFiNkw)u8b4{95H9YxtXh3JzCsCg7mZ^1rEn`$1>SS8m6i zLFu=hAhD6 z$kW0`S~t!i-X#Y;2VYDVUT_33tl0IRcvTodMJnQ+(>=yXm%# z)G~WmcL0Eq#yT-8_IBOd-b*a9E*5?*mKCU-@^K8(u;}55q-aPlDi{**Z6MfqycUXt z5vk0=re37TlI=ZU1HXHUHI6<7fdNyfL#ddeb;w%ZNTmhttas}PJjn*DgU&JKBRhm8 z@`tx^3D=`cJLL1lTP18cH^07@QiuAifhi=w2ctZtQJ1_JA$D|Xp#15N>$ z( z{Z(xyV!6#g-;A}5K(cYO@Nl_SAT8HL_m69<2>HOk(nYwGQ7(*{A5?jFkFZ4)x<{Fq+su< zhS~Gx3L1VKU61w#6s8Gz=Xn&pG)q5{6hk`KntvQWN+Rph#PL}t*+~WQJamD@kVCB3 zo-9;oPcMzZ?I+J`m5mtMeX0{ZBN%y=^V#4nebl043foU#Krz=aB|(OXlj3_p)m2q~ zTmpp%mn@kG`7H_RtTczWas#;UqQ^opH2ux=SxdKiaL9RN=iI5w!CH-OU9$1+F>?K; z!nK)h5ci0m8{DH4iEK8M_Yuu6g(iuGipN!xm?j{+rzzO&^Wd+wR*jY`u}Z;l_3qJ& zPfI!?CzyxFe~}ICAM)QTAY;VCN=YRm#^?d+X+cmRtmCP zL++ljEV=QGXTOD4_rg!}Ut-9k$4l1kJ7?+tv2iwE+iu;!Jc&(qxH;%qIXZOR$Q=ut zO5P#ZNit>m9)2o+St*&35c{RQ62Tvxrc3D*g14q*T2&Q{5rERgK*#4=Ij5;yL+od4 zbe^y3ok}2D#tdbRTc_klSU$HN%&{ZS?^Dfpcwgm2il{uN)%_fqEgt69UZZjERo)61 z&*mo&cJWcWCQtI6aAiT+&JwyBp6~B^-RN%RSd-8{ZqehDcG6?mfj2sA>;$3cb*B9V z1r_z7F}v;3=QG|#S9UCy0$#`H3;FU5jg8F@Z5OEpXh=O+$B$RDlZPJ6+p^w;JUOWP zZ9iTw*it!p!%tB+ISu9}qw3ZxG`8{l*#TIge3g=gr-;#F8=oZhmIPIA%ngJMn^=c| zpz#TCp)htU#pz!@a@sGcMBNY7vBquW91?9NXWBaTu!WtetazO}l%m1DGB~UM`i1Z% zOvb%#&!i=j9`kjTs8+r6YCuoE7hw&`3!cHhx1itqEm^-#ZKklvF4Co@>8*J0+C_%@ zb=$MoidvEullSk+jnaqRAQ5R!R(t&+%Y~|!%p^E~BR+6p>H6BjXiizqvrFRm2Q@yJ zrOoD1+l=+f2;EHohYOx(Yn3k;)8@L1o_v}=Bh8Y}{}_uorJ^#K<`E9Uf}}i&cnE3; zkyA{mR1c@JAxD^wBe@hS<8xO|gz$h`Va zhA?@r*iin&{^&YX$P&7U7d(K^##oN^< zvqub7-Joll<2(J=R+kkYGam`1#O%`J$G_cwoXjR${vJ-P4^B(De|_B}u5r|i)L5Om z9wiRyF-5#$`Uk&4wTuN5jnpvDwFlWn?8b&u)EyhD`hssu#MJPmhE@;f5|>}wTspLn z$3$+~oP0hVM@DA(>5X(xOR+2YD{q9AcRN(xUs>A6YSNjC3-;rZIFOqfJjT~h%UPsci_7?^`ZKOz9lJdspi;(- zAa*}2_`ScznSN=KU&GrAj_>dBRf>=x^#8Pq=2e`KvTwNsCrydk#97sisfYNBF{hjj zqojr%Gy4=BO@f97va~|&7UkgWj}soe6}1+}xL#be&E(L+F$@!Ol}3If|FE@Ck}uF$ z9_L|iA4nOX+tm$oMb>x$c~bc@bEvNzuhuZnQF8#jntruV86NeQ1m8@0nGRVG#qp= zP&jqnsD!(JdZ@&4CMGuH8*A5M>8;!gfK7cTOgEu*sHdg{qET^((P3up&2_iysL4BY z!_5YQ^>2^Lpi{g?D|*h{ov`FFdF&|cMHL+ul&NERoz3x=OJd%-te&_uZ!vSc{V7CZ z=&o?04It8VnJgH)8f0}S$>_-1jin80)M#R4Xj48D6b>ncJG+&(x zb=DaacyV-5UDQj{+>Hz)0Nt{_py8k=nsmw!T3wFT@sN@}O8q%lO5mORFY=Z(DIEm< z*>Z8k>+h$rZ*y^mLCvN+blZ6e}Xo|kX=jjz*lY=ed1Ch^obVvAz( z$fm;w(+Cft!-~mF4p`R!gft{>jh3|Rw2=s1bR8_Tb*u3K%?||EQfel;iWgae zsBra>?Uj3v_#m6}@>@#HZY86OU{Lrdx?&=BLHB+h?D`8NxJ|t|suHG`aHc^O-cVy`GTN{t^dz5JH@!oSo_DJZ z#2ac2TnqUnYsh2#Y8~^S^wxBT7j0*$3oJw}3wX6Hl@YDM%Ob%`B0(alLHwAjE9cEF z-oHd)lfhg~W?e|}@;de8v~n_iTCb7HESrhpJp8;0D--Yt@jKyy+&>S}+>@djq-rG= z*(lr4+A!Om0!xgt808kCfTby9N(niG>9qXz=7bOFz!aSB?~dt6vJ^9;z2V$6L%s?xoL)QWwyAulutaSSCm}$7Gsg=qFQ()iF*~ zl#Ir`YYh%5mGRmLV9~*0wDhSyY1GHm$5JA`Vf-I^6KZd-Vjr4?gqwzYh>|tgwGAt_k4%@9J%1&O&W{12O3MKfz%H(i1xXA~JXx2?V zxGU;gd~}6uf}GT&9V1Yfn@5>LZsvtCK9wei+E|_Ee@l&vlc1=fC?9qydCO*YfF@)d zj;7)%Wbr)l!H4=*KIKg&dG*qc&1cM+w1gYiBOkuXyh3ib*Q|_7Ps;68!#GT z4a(L!OM)cD++M}Tx>xD%R_l{;Fjwmo#yBDvPIzAvb^(@k;4hC!X|KvImF zmSz-7aDygXE;8Iq5Fiht4?c54(>Tg+;ZF9^C}%hx;_F>Tx26)c7E+J9o+L3UKUUkR z6*AWP$W}h4TCkVLf$B2_-ZKal7xr06j$U|HE}0Fd9l-Bk;>!ElMz6Gmuv^W1E{WCN z-x6A!m@kE@sCAJ2I;uLTKEz_-T)^!w`r5~aZ}ZHdUM_qH%97J#CtV#+(;k360Io4d z5G;tF(0=m;1KocY*3%xG!yno(I$U19QjL_`U(J4!($&seMJ{9Y+w2 zXlHF=(suFL&9$9chkn;~*!zm+1I;TkE~j6uUR(_ukj-~~@v>1Oy{cvA{u!(VVQHaA zO`tsMAm3^*aie8B?{**mSp^jJD>re}ozHCw3ltf7gA|XKSU&+8CO()3cGaIm&#y*f8WKhNXm=+C=A` z0qrZPp1@EKn^d#7oO*AQ0t`j)5#uql7_9oUJ*>C#`_bn(o~S16O;fRtHGntQT>I)8 z8l3G4&g}SvQWs2N4QxC|tVaA;jmZL9u3k2vEzk~lY+@xm*qGm{sW%WUHK{nL^R1zq z3s2@j=>e6kG~@j#q3#yq&q^`G<3RN2=vy^Aa?>$hvfA9^H$>{X zlbFFXL(s2L9{t`pUvzmoJI|W#_2S(~e;;_8*;_e`F!F=A~^u&EX>FNh6Ulvuhf;30Gk({)ntq=@LA za8gm$0R@dPRt;&e-n5=cW_y~dVT7Y1(xjZb=O60*%5zLNoR|Pe2=Nd+@2WDgZ^u)Hc}1lR12VH-)q!C;pJSSnLd4N~2Sf_pYKrzy;6+6XqO9AerH(#DiYKZHQf zkm^F0!0o;q`7s>)S)iT>6sW1_YwDoU|SB4l*UP#hPa)uq5d-b9^juT+XmAf z2^qT9ve9sEBP_-OT9f>!Ns=@3N|(9@Umgfal8dZ+lBY18h&)c~rD*eDk-hy2t;~(D zAAQU9a~Z}`53fS9$*Yg>-_Bq((7fiiHt*UwZ%xmAt@et9Zt}GqKHF6Fs#}Xx3=FGL zUML*js+-sNtYl*aQ>{1@ztZ6%lDU|dOu2q3zDMn7_)5FKNBLfvTX*7n?k0%ge&0;^ ztf5HCyUn?=G|ei5dQBMwGo`BriV&@y#nb0yUkm{W{3S|3jU|f*M3f|o%5@#Qunz8a z4lfTkDayvdb&Gf)ZX8M|I8r}p6v%mZZ|N{48MVM;ZB3;z0+}FoFJis%rZ^D zNf}0?E%&Cew>DSU;$XzM2%@mnVwscoTC`TTH901B(uf@9!2>XRd$$Y?#WU@_Z)KiW z{>Ui&q?6jpN81}1Xe_l_y%?60U?ne6wbgE0@@(^#qgAr$n$^2vs9EbR#Kw)BnA3e3 zI9?kaah90TO5Wf1)%y7R#2ZqmAe{(`_KN$^KgG^zI$m^7!FYoCRn9uGK}Id1w=&6Z zL$Ki#T}y5@-rx8k0EA>PQB+nCWOWZHUQ7oYwmjwXl2TT{y=~TN4+H1tH8<#SC{h9D zaXOr2!BhPP_fIF=r~@69#!(!+4l-R8GN~_5Q$!y&@!4AnmU$H{J@ccIYtk%e7qOB0 zH2o5*1+HKP2Ht6g2CqWvVn&X!88!kuLRYod*Rv%;dT3fA)b|pLwWd$@6Kr(orM2Y; zZ9)fGLv=E%sU}l?IDufnmE%533Ajva;uZ8qiDAOmu$le24&#gUa`g^br^Q?AtJh&S zm9q8YIM|WC%%M?ywqn9BB_)k_iiYz8N%>Y6_;$_@%W*H{*tZ@~9U9m~@ z98^O?%rKy__cfV`?jbje$&h9qGLARs6E%sW&%hirW%CqcnyI zE};j1Q4lGzX827)Jf)FCG-!+CwMFN=>HqWg?z&{8aS#6dNWoYm3dpG92pDt6Rv2v3dSTB zkQzDov2wQ6FK^)Zzq`6@X^PlG&k4`th^y_{w4SK8)zUM)Lq3*eMnDokt?B{j4kccv ztm4StQA|+eki{z=psuFzDk(8%Ci&@*hK&cIjuE=v3=&q+{s)3(6-MGi7itBMg}Z_fxAYm1iG|XmO#!F=lMBGUL@^ zZMbJ*GC09vpqv0d z^j#Tok|vF!gBrtJ3Rf+h^lx)A^BAxA6kl6u9u!Ww^1H#HKAtGP_^LqKGhp$NYYBui?d@+`HDmGtGplDP~R9sa%u^tAn-#v=k`P zIGz(F%}r{+OwZRMMwjmneEOl~{T0S1|3%`!1deq6ctDb|WTI2_?won^^}vju_7<_W znlvp)Jv`CyNo zX_T^*#HA&@P@-RWb19|&k*Q9tI(j0{#wqkM8h^#t53+9F?qmEH_u2gsmoT!V{%ljr znu{m70_Na^JKA$nGW~&LLn&?Y-X$*^pRTv^!xApwu^R> z+W1gn_?WSpLYnWi=jaNRZg}Fzmg;UrWBy4vpU=j-M(311$2@S)6@j7{2G#i|`cdGJ zUCQ6f;$;5EjnP#D)KH{#DTYt&3tK5dk|ZHq2^8ab@+>U9$L}{m&oORj7xtz{DWqD%v)j6Dww39kZILywKB_N-OuWC2(opb>3bwthQ=~7s|-Kh}kk}degac(k5YE zg9$NUoHO+Su+7u0UntZ#SnCS?&cSA#4P( zoeya`gv6_GaM>a)f7U2Az;(%lcqGSU%Q*HENsg6km+6Z(Ukg}FMPL0;QLIfE8>+fDG54Z3iP@50)n?JLeUC zjIN4swDNxLYJMdjvNvxDC>nxQ>uO{s=!-1*`~Mhdl6Hlwpf;dEt-p2loS6t0IaCX; zOuuWhy>NjT3ALKTE?~16g{B4n8{2Nw=4b2Cr*zNZzTR^7gLw;W_v*Id@>LdSNktDm ztF~4%gNK@0Qdb!}YtMZQ5NIQ;ZO@BW{n%{c-vQBD=26!{%{VD=I@?WnRBILReX+0`JA7+>B2^N{r&bAW-bJtg|5_NDme;NDUSka#zPf7@ z{*Uhlg;{=uf7ka2%jEop_sWQq*;J?)z=jB5eMWL}V18&XdkzS9Ms!$W=_2?8yoLti zBzV*{s^{;EutAUpheh_gC{XIk5+z>;cXp)0= z{2TBiW+FJut9*SbV3-(U%KNh;_}+uCdv17^%}8UO_H5R&{0CL+D}+?YIqj_GV71Gg zL@P})wx;_SAqGU1+1gC-PW1f|Ne)o?i%jYM7^vGRDwZ2&*-7k#m4!T_KUG+Jm9}EXln~I zpAqrfeb6!g4&m?$E8eayG=}D;+E&`3E=HC4eG@6p1%sIciz)kJ1Zr8Ylw>ZbSq?^A zp3zF{63AlsGr~n9ycg2K3M}gtrG#aqx5KXQ5W!E@fIhOi@Vva|A{>$!DZ*GrE?*B(yxa5w&~C$3fhcoY92ELm|} za)%_!`Y_qhYi|@GW0LnK?IV67p?H?W0`fbf|K>^*Wiv!eek6jg`IJH3j6Vtr-?me; zF%U4UBoKF`Euhb%U|SO3qF*qZhHCs&-%F3FoAslk_ixrpe88F`jlBMRY&{ed4|Aas0X7u@$@-Cw4{ngRMc6ilhXs>Uh0neiQ71yQ%{G5=brf196kKX=cZWl|2uk*b z#QDh#U+{j3Ya8D&pZ7iVw6r~?`_=`pJ2fJlNdfraI6mX$LY1`cbnufu0UaP z7craG9S(KC7=RuB!t>M51DK7}#~KU2rF;+fp7_oOcAS1Rloz0;@RsG|(T%xESG3y?g7AI$WV#+p?_iumm6AODVG_CoGaxo61E4F_!T(elkqMkGGd2VTGK zwPDQqMEiO)(I6CGGdq{u0CSVM4kU@1P;_XjQ^$N2tjJ&0fb#Ahztq_r376WfQ? znTRk2hQ~iVXAjri6>WwCf#t@T+qX+4|9DV;Q0M>5rau^d0D_SgShR7JfOqZYgnvx! zKVjs*!^@wD^D$hDbKS8+bDjc@Y?xifFWJ0|f9M#a>F&5e5dM^Zxfiw_Twz z49s1=w7AF%H{I=Y1UEdh+2A|HCwk3a13t_8E$(7`{qfJgw_*+-n4N=b-wEEmr{kNI zPqxPCVM`n2nR3=M?lyCgp7+$d5;7nN`ST}?I=c-D>HOmd*Fx0)?+<9lf?)srYbR7L z4+Y_`%MFsHa8dudyb~Hri}!as29M?G|8A#KJXJ~m?+?P*|G&J!bmCyRXa6@IyS@_y zaw0ErWXd2cQ7`y+2ZEWagx|8-ptT6Fj&|~X*G?XV*IuT0_a7r4VDFZqgU?#)*u>&^qV#6a41s}&u4KE<-r7uwGWrTD4G&Sno z`Z)EuW1vEodThvSMuJTjIBnBd!N_t)ztW|ou3 zENidzN9Jy=lq1nG)m1Ewez$2{xKT}Gp7LZouf?14UTu4FaWkacZ-Y!pO}+HxEv0lE zb?o-{s!*u{xfJT>Z}BS4hRGzQnYY3GD}#k1>J`3MwjC?M(Jz}zlzAI?(CFN0$!4Hr z*5GNW8bisc7d+1QNOtYGD9>~2@-UwAnfk1s9m`%UQl?GpI;P^UE%)V1=>jK)$gNF0 zgQ-JaH!p{zdAsqMhsQo8weF;gDL?odbwg!qv=osK6mY&oGJ9X0COk763hFuCnPq@N zaJA^6LFbRo6zvjyZ?^RMd~c8JF7|wHbDJ)@d{+a{<`b+_#`~CQ z_#A)j{Oh!-_HSZVFY*!<$t@c)u$I!PBgkKx4rlDp`)jWM>@Mk?x&Ag;H%N};SB05dDz~1 zF6MT3{D}F}fvY6yv<{FfI5Ta?RJdv~ZjAUX>>%ft~ou6$MwZR32BH9Rw=M#Qk?gVPJn z&5T$yb6cIyv`=*Ho4WB`ejQZYMt|-;CTijS{3_#zE7RvtldThyVY2tgkD>Tyr6cPB zjzTS;`lsnWp`>rQ@5>DyUH|09+(kPJU5}W8IrDeia*tTPws=pDJ7%Cq0@vM9b$+G1 znCB{>HI;-Z{LfsI*#YHaHlkKYA;MOMn+A zbg=;^mU>HL*L)E|{T5%lmWha^)3YY_?yB`JzO3|DpI(T)9Py}_o~xy<_AfOCX7ZN1 zj4xpiU(sUhJ`SfvkDFk?>G#}gq56upGU2#99g`&;`1!5x3|`!qdKVp|AAR|&eYXh; z4;&E;gFNLkpQL=@*rl=ECWsS~G}YuVs;9(~TnV6jS)Ww-{K!It>`I3-3gIWCCVf(0 zI0N*1gxPF?GKav~=e=7+)YYLUS5pHMp8gQX_KfJ*hud}ji-@C=WYz(!G%*iM@}|2o zIifMOa@>+kE{SOEDnpcunV9TgTqKzxzvD(8PaZrE>5m7CG(N^q%M-lB`5JA5Y;7rkarsNQM}P8wC*iWGOC$woSXRQV?vR(03jjKo?={~vP^cHnHPyqUlBc4Esz8LLCzfboh5Az z6o{qVeyQ(Q6@*nG3I8U$ZraP8Yicnp!OKN&hL`-AB^ex|GaO~v2%7ABqRegYE4*n; zj}`O8+jT0Zu~6O&``%rV6Mp}YKB*8y3oSI+_*Rz9`RYh9Ugr@Zg5^X(Jt_oszpDFq zbgC$xE)hfCQf4`Ib@k?Ko)vY;;dri)wJ(u1()L-cFA{T%7_uR8T<&YAcd|0n&Q?mD zi8&&-w&R4?J_@d@W+^!zbu|$I7qMsJ=Z_kgXwQykXwhw6hXjqs`um z!sY#1Y}D*>pa15)7QM$ZZl6&?=p=y1tikL2h78v`9&B4ZD`BmPQl`C@BOz}gB{bXx ztmi!|@3LQ+{LJ%LDKOXVP5-8cQJzWF%{e$eQ{y`Cu6?ycG6R*&r}HfvctY={-XFOh z%a_)gClx1r*4``}Fz<6E-+U*yLoB-nDXP&lcy!0^aqANKv7hhGQ~UY;L~XE02010Q zVWCRx8@!>kLFsIM%@edR2qBx)&yL{qiQ<=vLm2{F^hLn}cm%Y4L9k+P>F??x;z!?2;OLnjeI|r&PdGag9f{%FFYwgyY598W|8(X-j7w2~K`?+{+e5npMADk(ckU7B$Wlm;fe#L`p9^YSoDy#e!?CKL|HxjOj`Khf0ri#VFMz7nX{Iuo(M+Wnxi zDLSK=A7Lc0i#bKcXX^ASTJ(~mTd*t(Q>x{CN)0FS*_)j$bq1I?&3ozsLfC zH5^Z`!5jRHvy)CMHO|9z$cWi4zvAlHYjf{KcO}Pf`6i@dw0Cr}A21REt;`4?V^5dt zO%aDyOB6&^H0yq7rz7{Jcz$G(r1ngbJJc5ADfAh7Sm0dq$y%BgWAM7aS(MpmfwJ?C z5uCpWE~^y%sV0|eb<@qMwhFZ!r&)XjY?rf9+VgnCUsj@T%zla|{u%HrX(z)57Klhj zbnt}C{HV5XdK5ICFZU6*NQ6jG=#v)e8mbZs!F*LDQ!;m3Z%%Jugy{8J+nVy-Mf9Xg zNs54sN3B&M!buD~qPKM%bwn{WM;=lQ=KYBGgl+ms#V9CnG(r@%r_FZjeYDI&+p_i) zg5waJy^|g}8{Y=`mXUgSS}4Yt83wFrI!c_ee#x(_@(VK8jn_U(-2RKh5C?c zI~7&I+YLBx#5Ly}#UUawb}g>Lf*UIeno+?ErAI_(VJGbfh@C3Ags8hFYlXTZ83>kd zmC{0vmc6IBeM@!&eJP<|57%QB_7LAk+f} z7rBdO48hxZCGhHdokz&28Y=>=Vr|6XcuiY_p{|;~{rjPidi|RbvQpN}oq_q92oh z@dXktwm_G@+s;>OD?;_>g5C{RZt#_rjYcG$_m4v3|69_!SQ-CcGm`mUh z5q^4GnM%#PldhrSyR^tE!a<#(pD0jB)UZ-~lEhFV{}s{MCc6eXKYV2rsaGz)vZc1ZKDe`g_ z=coU2$f%7h?zMZAem*roR8*y(ON&hU<1;Z^%uGzwJ47=VCUu6sWX@pDPEn-uC;4br z{m%Q8$ zcvpQ*-y=;Ob^lmq8^B_L1VN^&`R?iQq86N3KvLjjy)c zR<+zx^9SZ0>t*9&^G9W27`3K30l`3TeX#zJB;l&>ellPF{@O@V4s!fW{q&{Fi)?`bwgBEy{(@VzNV>Xy9 zVMsWPzRvKHDbreyjX`Q~WL|B&W)iW+FqyGiCu$}SJwyku=V2BcT$Ub=xXEeq{7}mi zx;mzbHNR1zTdCBEk6C;8AuYC3g&{Je^Rg3eHpxN~nYgDSW;f>!*G_GSO{7NR+A&9G-|Ab|ImdEtHD%Hs{j)K0%SC-FAa|CxuC8Tw z@r?MoevMZk@hF3-OnOQ?6RDq*g}_YerB3?tT9Fuq4hp}|;w|@NcsH`nUL(IfdACn{ zooh+w5$4=!rYCD1>lvocQ&FieZDCA=v;m_2_YfP&v`JFZbHb(RsP(S5`lkRrBuE_l zzSAQ2*tKWNXgR=vx9Rn9w9vbP8pgimBR=Ljs-SZ+2czzH*B3{!M{9#(c?#*ge?u_f z1oc0`K+61hOh+)oYFL8ANgHcF(hY8@y9BVX&U>GcGUztBVTEl@m1pWSdwf$?LGz@C z%Dn@e$UUV0a-`3u4Pmhh@aKVI4*dF7y!yS$OyvA(ua)%QoWng;peyvgC(c0kAFcr4 z?SFp_!iPMae`vgD0>BcG#M{;MXP_4G+HtlOC?--`rCflwXkCyjHX3<~0IfJI{3~pxtY$u^j!T z{U1%j|7cl?+HCOf>ua|=+lJZ-5`>V0W?_Adfj$OL7n@k5vpw8DXpNqsz^lV=NqT+h zJ8BHjh&{lWc)voq*cs(wZ&1$uLo>Ia6TT|2u1d1W(#I$F73v??rtds1f%oX!d@KVJ+=Yv%;Hp zMG!`{>OhV>*vy7Ve*YL;$tUXXK#mGA(*9#cnn=M*NqXq6n7@HF+WlO0sH)jh}@79Mi`J!$O|3^D9G_r|O zQ6xNh`t1Sba<|tPCmP*Rq>dyvUzPOd!1+7<=#Ld+2VPPbbw$M1J1qBsU)_}5AD?9_ zjeCu+PIsbmTM1AjuKsP1;3Yh4Jf#?7ck#>qZ^bY3h5cdil3ybK-aC5ePtfdND-VoQ zZlXV)PI0B5rS%<4%Xx=%tIrL!d@8$0qW@m&-F(H%X)%BIli%)=qswVMO`%z3s@4mY z&J=9^^7bKPPbHIPrBoWH4T&efS;;SdGYRc469C0-wW?!)JA>Cme5%{D@!u|obc8W=0t@`Lquu!M z2oST|g23|nYg_->1xzyj7@OJJ-nGHB^sI8(r7vNDOmH6*(qC^sJXO-y1#q>i_79f; z8b~fo0y8Sx_l|+a_x4%=78aJ;pd&~mF<&-Gfr!)kzjg!kT7t)Ad-@3xu%F}Wi^Ell za%IL&gLh&fzb^nZy2^gHn)K7|%+xsk_t6R6o{P2I-Cj{Zh}flQXwMJz zd@jEJx79}wgsU0yyD1@}{wPAf^#E*yzy0!V9>~8u$_VQmofpTS{NcHeyJ(ExOLc!9uPU83RopL+i;Vh5RBJ5NnloSaf{(PTJ*X>8$a+L(nbInI{4p)=(cqga9i30rKy+4`822MkKTA4K#6ZHlG z?a{k1T)JPrE-%YoeO{YBTn*HU_49-2F2=8N+0hCkd{zJ<7t~oB&MY6u5YSHLvU_^4 z+?^ClB^lB%`QU8yqZ(s(@jlY)7+QIvi=Uz7B(ec(fDDdfHIita`~*LYKUL*^WZE6K zk90U*s7zI)*V=;m?#J)WQ!xllZnoBDbxP0InaP{A_2x8<(_p5-@x%6Xg_v&_+cWxo zay}Qi(8Spqt0bKkFU{NQBSrW9MSrKg`BzI{!$0&Z6JzsZC2Ld|Zl2GSwMTqR7U8(x zBe9}3Lnm8PCcv^Dqy#9i&pxL5x83t}bqmd&b+)cor#9U)ZTCzC1_^i8)LY*JB7YLO z6t?F%lF?6#)l1{jxa@wto`T0uE^oP%i6RsDc;e5#j~11{<7i6idi^2OC+-0p;+xFOOx^X3(cBZwQjH4Hy=>iPkISb0Bd~AOWLhrP zh#8b~g1~v8n>O;34BUy1K_xE+%*Up;Nc~6<`W{k7&4rI}i#>$@gIFlW=4}jFRS5dv z0fiqo5_LJa?h^6|9h#|p&%A>0?eDYs56eAu`ZXa%VY=*a_3}pca&s>9}WZEkO zLvmzvOV)jx+m+t<6M6Bw1VQghDR9D8tHUB}ETTy3f3o}RvQsS_t%cWv)3q2~6nJm?Q z!a7ZcBmg>JA5 z*)Iw+YkY=95zc-zSgkbu+<+j*Uk?@Q0lT~?c_cgvj#MZHsguALxM1_Dg}#w&u^L3m zJYjvqFK;MG`CKLfxZ5H=6b4JhQHPy|iNw<*i@xV}Fdj_hh!S{C1OFJo-_KrHU+Hte z4)%oGM5*>mt0%h)t>p-=JxNyfy4#^w!aK;ueKne?RweMX;Ap!f8OXX*n5%a7sEwl-M$?4Tediv@;EP{auGurNGiGlx%rTJG2m=hye zJVf(!$TWGqka=9|Xrr7ER1P65nIj?!F<@WEN#ln9i0U5e=#OZUA($P_`r_h6DL;D# zV#u90(QC@|8zB9sqNi7HFM>8PooM1xUhBoR17upm=e`%$L)Snrdt33M1w zIpBT;3>#1}6|Cm;x( z?71E0uS_YR=3~J&O0of4!m8X;`dKhiFe^Vz08{L=1HY%BUu*m0WA1yA^O5%h4<}$! zk0<#o$%hf&{eWPUb@IIr7CHhbB zeWZne7;J<$!^-=}@Kj#J27)?%K1nv%sDsuT1K$Im>Mf!_qDY+wvMi~7+0sOo&I3cM zF{mU+k4+G7q$p(R2gI;O@E|wF0|5f5a@oVuTa%?HxAyWimfyylO_h%PF!oH5Jay3W z+Mlp6La`o6!5d@c7;rL(jaZ{~Ao4)M+erA`lxUDiPq3TFH*f=IXpkX!7&ji!7(bp& z^vlosSO{-WcgbsPriUT(+K_sz#J{68g03hK$gkI+LZ}gL_(!lwf_1LLW2=NH&palrm&A ziOO|%j#q{dkd>*b*_mh|C=xbUWu)uEBg61D-1KusH!+lAPH)T{Gal*i@gC&n@=4I3 zW$c5Lg`-FobOv97BTz>l3)X47TWN5kFgmttBpRt(LMUMb9#JL8)QTX3Xz&+Q_yHoX z@H2My=)k6Ia%^#wN+gCr@$5+ioHqqdZiq2TkgABS;QhsnPMrS{O^j}%B52~RD0A1M zqAt0KQJ})qkP?s8L#xH8fW<Jd*AEsqjXm6eELF9CBli#jX|z^YhZ4 zY%Y*TjvXE;$KQKkF=I3uX)IU^w}~8!yN4))I4XGbD>N?kf}{d-1z~oPN5n;^9Q!aN zJO04OfOyVIBQ=`x_dxDoK$(yh^80b~8}14DBi;i}wl?^8fBWx|{hw>)chL7okoFtq z`U{`R;i0c}w8xC8eo#mNGK#G^=44O0JRUDyPJ%J_@d9~XYG->QwPEI+k96@FHov6H zT_OXZ7WVl4cM!0#au5L!r&-XQr%HPil~i%V*W))dXgriG_}XCj^~KRVYrnT{aC(1% z)ZS^N-nr-TXejx{JCydj5QDe=ATs5jOALrqOBB>G2S7oSR;p_W|^bPWOIU0@(K^mdQa?B+5-?y?9>mIzNRnk z(XN^BIV=S&m%sV~e^g?ivX3cr4HX9=VwvLvW%AxmZnR+K+%Di6CwrS6_@{bX=@i}< zUg=lv0%XUN*h26QUm;VF`5~kFgmjJ2#R@K6@(U8jPLY6p*ZHC3_;?WR&hjc|eG^}g zWd+y(fY|Isp$iZv0EU3+6777kJ&;$Lwxt;+IfcCHLd4{SdAX41(N{yw=rHs_pVu zS#?9mY>1>vQ#npZ)P2)*+81PfeSHB~OuirJ$~~4C%a`rHyIHvF{k+#w>|0JLQ>LF| zAy*RlqDbZW?Mb=sW^Iw`2lXPDUUEK>i*`(>{_nDa#iiOE zLkoXu0a*TG$&zRoDc%+k9oo_Ujv#31tOylozdBfKhbw*9aTOrl=nXd5pC(9B282OA zh@cJ!xfZw+5z$TOyX9^y#tRa1C8K#0TfF4_EoQ2VjHEXR1w7dAPrDq7LS;=(=fXUN zSe><@bVlFXix0~zVk2|So-aSXEPqOawwf54`CRS+Camgbb!MBchgu_X?c=cV%-Wnc zaig!~{QalBPQRN)<>!>r?{l@PsZg#D^CSK*QY=*XFFX>v-?$ZkA)C$ z+ABuk(O2Oo+?X^zwOs_$-8Oq))yk{^_Q6>QSz(_IX?_X~|LKN9fnsLaY?)@2gzbFO z=JZnLqTnZtS$*wo$AhKkX0q5ijPpqBo7xSp^RJJ`6&p#~-9Is>{>UcBEklxD1Pft( z`Y{wM6AZl<%*ZN0SFb_nee)RqDvMzrgrZy1hbO@xgu_dw$GN5pNnT9Dt@d?Jy2lcC zP_N6)50~LT)&5|?aMX7*=BV@0)?>*8Jc2Ied2bU<4u>h?LtP?c3XEH*p&%zKIsSzG zip|Of#5Lfs9N)2L-gvpJMb_q=T|NYel4{d#>t6qL|7ab-grwd2%1Tf|18%`rc~Z;V$DRUC4)hww`a&y!w*0JYNjI5YtrBwup%X zc=p215O*UQE5BABI5I6Ix1H}*A0|F3skAgy&mOw{q^v}PTowzn!5G8BzFC{456UHf zVu=&;iIY++o(XT>fqD9oZ$F?>iU(`<>jcj6-xpp8M?$FKNPl6H3zpPy*JDaed@|^) zzV10h~^8o<83k7d#yEb9*Laa3+V)y{#YGa0(BZIzw#C~D@9Xn} z6Mh<*cOx??45|g@s(ehH&M6#%;rJ|*GXze&R zLWDiO04AXUT;0%S*VM4@BBYNH0dkNl=R0^xsv0(y@(OOW|$`NZw z_w(-tC%?YUq{5km0n(tjjaufNR6hLRxbnEaXArm7(IA(H5SQ)T$Qf=8Zw$*D9Amhv zr3|IOKrO5ubW1%74L2JaX#Es8Qno4qINNF|m(>31v$(mLbmMY>ML|VGeFHPL)MH<@3k!@!5temc**-B z{sy`{=bVoLWqgS)su6%;Ltp~mnmqD-$E2MF#|sTd*IzpRao8MRLkgCt6rN#6+fW>r z>kxFXJRo4JM6)W-yk+~f^^sTqa&V~nNwJ3-E*nUZuD#fRTS65#yt}<=YzDVIjP#)u z3xUJ}Z24=$gj)ij<$xYE95R0gbW7ur5--qy4~z-JMUrnH)l?1I-l42H=bj?LA=d|3 zJ&$KbhP!OIhkqu>j{|R%#$g|bJY!Kc1nF#O6)obdfv4OJ^!18VX)_3g2kZjZj5H>* z#X>0@C$n5I<$ry`s8QE2Lxp5eU9Km$3&Rz*x7Xs*%4M|$0fOtOue}Zv3*|b1wYA1R z37bk{gC+5k_14q#uN?~4Ao}U(h>dilvFdV~(W9#Fc#N8{3b+j*zIxiaz+>s&w7+QM zt#9u&@km%$$A1pNPIPT1j6A^4RAr++x`~Y+&mTKJg8*+LKBOZTzA7IX2IPuJ;4q!fVCo z-x5#kF7g+?5*5OqD_28@P$TvKnkpyHLqr^$x8DQNHq~5laa-0!8X@XH@t^am7^){) zsPeVv@j0f|!x#9uR1`iAskkQ1GJk-kjy`hNXz9-q98P7pcy3}(pgALNZ*dvoY2&<$ zKWLLNHl2^r8=D7&2Ji*JJg#!x(_OCu04K{1B`VVAap6~gCE-+xNH@X4i#8sIbb<;r zLxdDRXm&J2%X4u?8BsU|wiA0{voM>{$6w~iIrz;RLsB0@(j%1g`Qd;%Hztb{ zA$@nB8A$@CodtgCE&+{AuiUKY0yA^<;2>~dKO{ItLh!H-Uo)h~ueSZ6 z^%dD$?-NPY&2qoO@k^1E2lDe2tQwfgZF9`#Lm@+Vz*~)9iQuvyi-^QSCuSCjMi^Q} z0ui4Gxs_od9Xqxsm1%@H8WMx{tTt5Rxg89fC5wp&ymU{uzb`lWLTKSBh2=3%J2{qk z#Nq(UY6kKZ*pFTm=R`6|V70U04xk4L!4p`(@0cBgBUbuHxnN_f>W`2;QkyY&kWSA4 zkS~sNL%nM-&`ztoUL7bSty3nDShs|H4G(Y{DoHW6zKc3MKE>|8(L+Rr@D?rG<$PP9 zeK|5PGmC(DmE*{dx>ji8S1&x&F@uD-^hOH@5*8sUBo504<1S3D$-XMu?cx~XTZMph z8@M_z`uCu~1ppm7y8?9Jp$6LF#Y&Sn;aN`t0xYeoT# zz~Q$4U0svg!S6mom%$sN3O-zW2c%vycSG{4ZK)~PV|!m8LcWqLW^(o{P+@V|k|aEw z!sa|$>CL6GNau4MI+%J2^k^>tTQ$ZbJMtLTSL_D@Y%r`)?bngk_CPIsyd?*I2p^=V zePm!7=@8c7HU5NcR_`MT&(17C`ng;}-l5QCczh-umee=drts@uYm+e%2itYf?qbk- z9;BxKOrCxOXpQymlMG6_!X42&eCt3qR7-mb^1>4ldmR$Avo}V`H-T6>LLp}JfXCjA zZsDoVSbVmX8%9_LCqD`Gsv_)}thJdvp02N*BK#wVmt((=27ecJuoK3E@tLmWRT~#| zS^BwLqP!K$`Xl^U$xNFVmLVHVSX!E@%X@S~{cC?J5EqD%;0{l|zB*jJAU)h!70}wk zQ6B8lxwyC#xnP@KcQxzlF_%uz2)e&>oSZDX%zD<$%){g)wbzUHIdPYG zY6JeApdn~E$X0+D{C^L!{%@pI|JQN!|LfF$q?!M(jKlx4)c=O1a5drAfRu*K@C)+h zY@J>G`C&f`spKai$taRo0Ma#e&7>eC+)B5%S9aalUUa{2!7wJ+`!t$#GBg_`E5$*! z{m~O1$F+ALmC_%KhED?8S?-Qb0?Ano-SUSiY$ju#=Ue5iB$E5-zsm{eDv<|3VueQG zJ@?^CFK%fpawIODf|RhZ-+SOT9pJB?c^sSfCbQU0FG^y;|I*7@28KDM)AJvNKp}LTN&vqwI;iC=+{iiTu4dB!x#ozO%@$^0<7Lz3@ zr*-?LAQeKJ>2)Ywk6=1csGQhc70B!SD@a=(#M%su>Ls7}b&U%Ep@>Jo^>6O!UcJ9E zn9;i>o%T5FUP$}%QS!j1swUYm1`gdDMv&`@VuT1_C4*F`^t?48b2R?<&AFT?FK>&a z)pa&D;eTqK=7$2uwO4n;-G;p;Op)hK;9Je%!xRlLJbE zaCYLO8KAm=^8ZV25c9@h@8f11mo_apUO$Uq(7C@hO#tcBZL2NwELt11cVF~XUtq(cvpk^OO#M>bm#5ZZ7j27-a8{c% zeEMIS2(015!TcX_)CM}G*%eykgc<@?d3Xcq&uz&U^cynVzz+CZUBwR)HPZ(oC=f?-PGacm#&{|9pMP0{Uh5EOYN$$KDCmmeb0|53W&K zw#1|Syr1PU%F<|B=d1VjfK2S)?%)I249%9$l~WDdpkmD! zXqDNjJ!NgQLQIBtGh<}0)Hi~{;zOJga*5ab_FV5QOiw$%-BddFiW72uikBmtlz+PW zs_aUils14Lh@0ieX5?uhznDN-LHvEem-9=El6MWumqhC*c=5re4 z%qytirx3HWFfJ+9seO|tm#VZDwZrHuz|UZG=^T@XvMgOHlb>gsFc!yYqGF-@Ax;@a zfPt|9GoIJWMLP~x#l$U;I7}1k6NLGpz`&a{SUIOBze-u;dGdBU_##Ue`h1YQR#PAn3#wB znh}j&eFAk=v{qpy`c~I`#Gi(*01cu|vDV|1e$Jp>P_5D^MYh~HWtn{m1ocm3Wh0ML zx-nVslH1Om6gF;^Yt^v+tY$Ez;Cb9K6GgvHsNB z%ujMTvN1K44^m8MU1v#qPxoT|j*Id^;YFokm%W%9=ca?hwHc-Y{N%K;6!W;`@kD{1 zqAfWGYN!ADouvL`uYb)mnn;HM@8Ub`FyavXY^+FA3n4urdY&rd7&4n*Rw4vjlv3U;vp4V6+UkKIph1X|5f-p|&&02;y)Sgi&*gNIVZ-korQiUKq2 zG4ngb+GUt%c*&oF|JKvROg*^7y>{C1^Tk!^`f(iT(vwe_5Y%dz8v^KSf+&Ac6a5dr;zQtfl9G(^L;s{{@st=d}yd?AtU4k1&)ox=H7wzYe?C(UDvlKm^FBQhE7*ko&PJ4m;4k$GL z*3+SSjYo>Iw4C^uzwy&_d#*~!-Yb*NU-5pXRtfFvtwr3{hEdETJaaqpg+h*J(Jb5V zW+k$nL7q$jyTgP1;z1WB@C;Wir`4dbn~*_4;gzs3}GHf}YG)|b?tNl*l5607(T zeHnwHi~kHA_T2%4j-O=w(!D;qm!mM>OOOw zN0MmkPv*>LN@Z8dm=}=oM-ls%I*ytiYiaiEZ9b}W`DvuFechw6N}q?l3E%W)xQdDv zKIU$Y_zlUckzEqsMeQtzd`w_`!oiq00xJ|EH?&0H45(2h@MzXBDVTcIC80FQ(v%MA#u7A%~#c&mR8J6X$wapUluyqy;96HS%X;6n7mzy zqcP(3ZUF;y#PBC2!cs>j$!PxOf!oss3fS_MGDfaZDU448ld>sTBFM+?=eOgoaiwjhwC`gNd<-=|1YVev%tDvuMj4i02{(7rdtuQfNG!_?%Wgl^UcW zV?g?;2T<=OK(G?WliPawxxMaI{c09Hq(Gt+TOx!}z4}dwPJ;^27f}IPGpREaQx=fC zG|qi1V`UEL%inG4_(K@oYLf@>F67usi|KqUAa6X@P3HNKEuonCVvGQs-x`sWL@^kBg{ang|Mo4(Xfo*{6`Fj}-hdhE zzF*ufAkWQ)vad)7G?Q`nqP`3v-`)Dlw(Em#@+WNHD}i1sRnL~Bnm>xMd4_XBD>^rA zooHBS!?VKo1X85jQa>4>Kc?K%xsC*ffVZv7qozW9MaC&k^B8{ZIO=&ElY`gJx!u!F zhf!C=K>`N|s@%puE;dLU5<|)^)E^_*tkdxN>p{{aFUTgvgCuv~n|T|xzLF?2B!Yud zg@iGcTnY4tr7^HYnx9=t^W@{Tkc>a^CNcu)Q?7TyllR(IuFx@p>3aPVmyB*`--cbF z50mDzg4pl5o>u6yfy1>$*DFJ*%2u8fUfC#e7fTm4DLI^I>`{a|`p`nyL}yEN?NHa- z8E(u}UQ>lkty4la1cUsxAhLg??^0j<0_?k-7)(}rVxw9sDc6D2@m+;cx6FZPL!_w3 zB3Ao6Oh|#kd;07Wz1De$e9HCpOy5M1rmOnzy|S?SAc?`7uLnv9h#XJF8tdYm7~+3P8S7=t z-UhVsfA$sS93U^IO8-`z-$e>CcJtT0vTyx_=_8-Qjt9=>+s^HDXD?S+mab6si zb|S@K{v*pD--hR0$2r?t1Q8(rv&7ApPQm__2_czbV#10t|Y;ex@ay7Aw zq4jB<lsYtY(U{9)@< zGUCX9n#0l4Pm2YT60u`X_I}tJHI&wtyPHE&=wr{nfN{*52kD*5T~Q3Jx0l7sSCH}=kY zF?J)JXuK24v-ZU(EP4;U7^98ucFz$P;^bz_wJH@v1W-|8J5!qvA1 z(wV7t=kui`gdEt|wmB-d$e*dBd$3eG2n(D!7r(ACNS_jTYm1^?w#mKcR(|`a=R~WF zxx~xIK7m>xSr~}HSL(-N0#gfs=GlTgZsf8J%k!U*GbSk?l*J$RN|H;R4s2Fa)qLYr zzjkwORS<2kT(kF%BuWkkSZ712y$+p)E4nNRH6L};`oJwxi*%sQ@HBg$x-j_H_p)r` z!MNwPbM-&ZWv$Y+>ujY#oq>sd(wf5eL&SaE7f-dtiP+64qRE9^baui;aI2WLYv1@@ z9`k-o{#Nnk<{$Xj(+`6poyHaxC9DR0`6yk0oJzRCHt^!bNUR5lh%3!j+3(5KQtuR_ zrc=c<(O>Ee%ph1v%q-hUdiX44b0wZHNimVbQ363==w`XnsZT$B0H=JE)$<;`SvlEh z+HK$MWUeNjnf223pws-IreduUkhN=4>epy19mvA~wf+{2tt_0!8j?oeLrVCcyhB9Io|Jl@h;j7Mz_z zFFR37ecIR=-|YjaqrV_^PyZ+LF^VvJzJm9&4KG3qnRO{XU}##EN!rK^zNMj-fBS{E z$^%p(=6Qh9!e?W}ufz_*3FX0)8y*`$4jMdP#~Tm7QwTQb8?lY!_93}AyvA6sC?g8? zI%aMksY_lJv^$ks%6yvtfx(Xis91V4KJ#d!VJuni378(S+@ie z<%vgC+42<1#737mQj@b=A+_x#>kU1mp^m zStB8v^D1dJ*;$RYL*~*z0WfqLWx}mkas9m}8l&uL;`DjkV`(o zNOeEkfeC#F1bY*KaV>o6%H~6Hlqa&@OB30cmO&fao~1y4Tut0D*m6YHIUfR^;Y26=yv;7&Dp zFL)M6K6o?)j*yGo#qJ^5#p$6f=|%CYWg;zZh!4aSHgKxH06iAwZsPS#4{s@gaAx9o z)GbS4Z#&bj3B=&nL`kia)hoTFuTeB$bB~`;qDD9{9ovaGR;kWD+T`^k@>dCd-8(|Y zyc$}3RpU-%={0Z?J!Cz;W>dCs9h$T!w7{4$mjAA%>!Ng05^+SiRk#eM!MZ2++vTVI zqZ7C%saUhv&9nDUopGLcHf00dfKA0t1U!M&xoN~Upw+nZG9#-Q;`@;Hni{RuJ_B0FFoJ`ko)*UD`?&%#)^x`7w>@KutTS-seX{WL0JQ^aoDK(o7!RclR zp?KdQJykws+1Z{$MV5h$@`D%^oc^D6J;-CtVjo)&xJ-x)dYBI-CN#rMJ@Dm zuMKlyaMx9!{hMuF6?57$wc}_b7#pfgCSZknOz{pEJoiX*vlg`ZoVg0s6^N#o_O`41 zU}<<4#LPu;366bx-&5AyQvjDPmN^J!Uc^y1TQ3=ly;Y!Bys2KND1O%k9=oUd*q@}y@J*Ru`d++^>dyN11kN4B_e$laUv(}nx zUh|6cJdWQnt*=HmXfzow*hWfI_C-FOPR6hI#ZM^hh&B?*p1Gy*f0Z&lJ*g z!%Wt#?-POcK%Oq<$ymIhd|z(87s~hh7^P1j?(?PHY7kpkx_M^=$E`3c3RTKl$Igt>8b4$YpL!*D2QXi0$30CoBaur0$ z%&wB_ga|Ty=vg2$;q|0&@(_Hf;>wMY_K^x;PD+TLB0UlD+cc#<+XM;MIw$!9WSuY?Mr+NIQ+aQa@^~=Yvv^`QyGR3YrgmZya0?M!eR< zgi7f0a8m)YloVu?rqmW(?ItHyG|GFo$Wk%h5UQw8d*~~e7kV&)n&(N?&|Iy$7={Q- z`g(3d5h_!ymG@f+h+^`?&eE?}3rMZ)Qw~L?Q3zr`Xp%dcVLBM&W8@f=wbr~8G34=g zA>9m9=mK5ZU>uyWMI5dg4wu;mN2^xe?IJjEY%xzH8~6ZqHMO6&F1=uKHB(P|*xX=S zc@yee+yfI5r5xc+Ic-D@<6+@BseMsQ4(=j&*(p+3T}=#RP!7gDZl1VGB$}3+WIFki zYNY46%_!DLXUk2~fCgtxq-u11YrfatCTf-CW(P&$;mrGSUiJU{z@ znRlP6<=P4XmdXD3e#Z9FH#sSjm;OQGM&HU+k*f2!!Pn&IE_dcR&Qx65rA$`WxNGy>VI0QnTv9W@%Z#aTpt7o(D|M4 z2oowTh25;6qQrA;sp3KkeMq6cV)&dq!^f(hwz^?XNIlm7{Q5cZPoFBj`y73eUy%(7 zAZ$d<3nl07TEEdUb^P)&Z8!JYd!KBrbtmJhXIv@0CP(Sl)YAqyOZ-vMcQOj&LagoB z39zFrzuw0G2)8O>16{PuT{eb6ZJ(7MbF$*{R<9o%@po;mMa5Th)qOwY6BH;OLWW{_ zrV6u3cc*AoGz`XTU%0kSq@^fu?mh1heJj<5K(hdXc2i`c&bAIuO)+jp-IN!bc!pH1 zpJ6DQqUXhj@TakTLzu3sH@I)zuzs?dD=U{PqIWH9V5F!kv*}u~mV@wTEqvQx3ybaA z+U9vOv=EDGk3(SxBBQ-h^uK4kOT=f~J~a!E=`NjREtE4G@QcdstD1?>QuJHhbP~l& zx=N9Uvw1%NoBe9qQkNCGVNC!&5w8h;8s5}5y@yWDTw8Uh6a4v4IMy*FwAiC5N7z|M zIfIcH^phXhrEn+qY$QW6;Jt=x?Q3Qadlv?Zl9*M< zOxVOT#owm$+bP~EuvWY-DJ$MPv-W_ou8owf_xxPv$$CIe68c)ISkU|VoQI41v`(Z5?8odf00$qe?*Q$R4+R1p zaQ!WT3b&CyOGWC4#e<>1+B<-!cBW6Y$G%=nQw$nghTPk-?1n+aW{RuO)U)NLnwxs> z0hPUh>Htlh;51S}F}W=%x1?XY{ddTfZv~xw8TFXv(r-Y`Pu#4Ixad7AO72M~s*3DpDDD6`}}@EneQE%?6HJ ziO6r~z^8IKci_q}5`_Ajt!+{c`nx(;MPJsfQnqule;A;NVy#u5)z+>xSK>&y^tdQn zOx~fFx9-Z^7dwO6XHc75#|)BoqLJr)OfQ^7_?e)($wd(Tk}<&agx7&mx%2A7-Rd@nuHH#URZ$DQxdyV;_kzAP~p%8m$!3W5fb#s4E z2YN`pV$QXOiIlnhBz9^b_oHJ*cRexH)-L+BGss9c=QFV%AnJm$zu7tGi&Ar3Okflx z*aXDhjsfqd(xr{v;;iDOwX5<^(HBbGJ%&hDm_ntQ)bAL*{CGFFV8qXYYJxuUe%MaO z3!*P`;SM%W;sA{(_QV;wX+{tGI&`~H`5*75FY%gU7Eh9~-h+i;idRj)N z;r{wUyli&0vo{Qdgm2r9Jqo{$bgAlg(3m?I*o4#k(M3Q8@|sk zVb7c{azm$fHBpDfH~(#!Z3ThxlULY;u$V}A@GedXt zTrEN5|CHaf>5NhWdu+yNednf^2XDeQhH*pWm*RW#Xq;$&`!r}K1}%}`Ja^qigIMA zB@2?H{}dyL|J9dg;2om$6r(@HIm*5 ziXgv~Bp!G=R{9`<6K>aUhOOMDCh%0@l7EwKRhgl*6QTU~Kc=8<0UEUpT;k_B5#oBH`?66DvxM(%0u+5Po`QZqj^9cd;7Cg#5diB3qE!Lee??t0 z*p8LJAbO)FxMZpKX~;3~GNPGywOIZF@X~j|O+~Oa{k5KVTjE-ip$uubIoEZ`cX!#D z%j_8d8veLSNou&mkN>*JeOtJ@JbzupbT0h70rlti5%~n+9srHwf5R`%B30FLo1XT= zoh1bMpk1iTeXv~KGm~r*;Osbca&Wj*GW)I6g5UqpO(|2fBJzTS0cbcc1|Dxbw7_S5 z^`EbR$@}!UIzuYZSkz;g9n9O>ApK!NOxm;}E{cfp9!5d*>v{p=1fyCHrFx$oWw%uPhVqLh3&6EWWt(uwA&wL+!tsd=T>hBz3Wp(D zUp_79(EWjBrf-F-2L7&b+X>s z->_)WUP1@}$_ea@aOwT(rxS6&MKdZX1ZP3g=8rTG*w}G*foO_ODdSNc5;J-xeQd+EpajE!_uSzf-E6*d|H?OyucL23)|!o z^imDrwdg4QN?kHuoMJ0R!(6LuTWf0?%r!4Zp0%tq$OwsInZal z!NYyP2Kc8M341fmqX%ctunRT-Oyke_LbcLy_=ac*!CbOn*U%8Ej|4Gf}=-tMG2MBMZ1Yd{^d^E9} zvmG5Pqg8ab>rsZ&;HY*Z;}`Uo?Ij~5_3&9bzM}f+ucwL>Hza~Ho<${}RQw|G`N;O0 zZ%m~VQH2Hsf>g57jrLz(ZLUwr8tsC$tu28gzB5zomPuprH8}>Jmm=?byK&~c-tT-Z zF)?v?7>pfP?!Kg(m<)gf+b?{GU*3mkLXiFJboGDcRI}cP7($oPu?gJuw+h{P0%Ji?=2`LaDBlYi}aTHzD+qjK{0j(Cng?Q z@A>9?PBEp0w@O~UL#A~wQRes?by6S{s&#P5Ny`wPPP{jn#R7 zDZTNQDR8pE|GDN<8Dx=5Ohphu&y^D`PY!oR?qa_exaP_~#*`$W1yq#ZV>?BWI+8lf z+5+e%$uJp-Bw=BxwQCl-?5~^Ay+R3HvDUPJC+q{Jq5jwSM(m9#p(QRLvZFy^&%h8|tElM3AD)5@Y?T6M6Hd3D}rb0)%ZvcbsV&X4A(OMf;H z+e?!o@cuK#f8^vm8A*Z)Iv9B0# zFiW|zED0VNy0~}X#oX)`TSFKWc`yNr{=z@(sOvs3{y-BM9j5h}fg3eJ)ztw5Ie)Le z%t|G530W~j2?R)m{(5dU`f|cB<7HPzt9nYAH!=A`wAxn3s;Bin$RW(9-`|&?Ae68v z|NaH|xe0W&eosct3h;A3aIXIGpY-RTSp^KM|K-0JF;nfimW9kg)}1NmAMjZ;D*}xn z57q*nBJ@fBz07Hx-FX1b^TT{gS&Vq#;x1mtqY`ynz+Xa`=-<-+x$8nkO&p5~Di-Nh~)IiVcbD>9IGw4w3z11{U2RhtF{DZ+t*_SN|FO7j#S! zGOykbNj8nF1c3dNkfs1E`Kobf7Br0PqRwHm{shU??E@W>?=AiF$n#gjG$;88O3fKInZRP12UqH|ZSu6dP@t z@>1HEk&w5mIsZCpbGcjnkJnkUJ{NOU-b}I%ZEJXN5!tuL zN~HhHOE)`*!CGmedT=u5(J_7A*ZXZXxQ-BJV8b^9gDk15T$`Wm{&)qN`6r221Nc60 z^Uizll#6H4MXrvXvS6?#{ni0*gxC9(z6K}qM*Z*eG&FnBNX2yBhD$9T0tJfaM!s4) zE9_I&MT3-*xKfeRO=DnS#CZwoe+jHf_?C_NZk8RsNIb4~RXi0J$(#`|exVkxeEj7F zewnyU*SCjHDB7klWnO+R#) z5UDF>6GlD1RU3A``4QE}86e$f%>VPebL{2RXgF3Y)4gm+@*p>TPHFL?_j9G!cresK ztXB#bD&Fu$r`y1AI&CacQz=3RIIY-c2&0)r*8$U+~I#SB@tb)E=)bY>A!H^ zLh1qc0hp=ywd{K4jmtWEr+d4j$iB9~pyE}$$I3|C=f{-)L|SgB^NMzX+G^G_ue0xOd~+s`Aw%1k+YuajtL?bM~W@h z6_#ElR}MwR1JefbTJDN0fbrDPB$I<)oX_2GGin^&YkcDv0#DimvBe&)J^yJ+#4A0Be8d9`eekC%>s~WAaz~ zJoc@Qy!S>sdhhOZR-gajjYTyt(x7!(7br8?18&{c?pd81t8Y#~puK&v*qfIWa5;c~ z)d7?PKHN^!HW>ZT~K&<-QzWUiFu)9>CQgcO;O=xH2w9eBo+A-r&NNq)e zN3)F$2-RGye!Xg%^Tm33cF9rv<4K`SE6gCzbDfQ*vEAYz#-tBz1+-_|snh#`)Y%$a z#)_KkycqBZ{wCXg5({ebGYwY(Ha)XZdtRL6O@8nF;Yvyjta6hzBcXBjg#1{d$v_R5 ztGELAatrrC$!GE_X6p8@{!rHrHhOp0fyBoR;|RloP}O^&YYlPSuN#0_dSJqP0*%r;2` zVO+Tk&RLF# z6uTBR|76S2;A;1`Ig4D)R3$JCC^YXbnbz&~F#|5VSwN*EI|!87mXkjh!#dB!G2>4E zoM+A22%u<-SCgU{O;U}!(MF(`)NNrCkYT<1?MbEH$ep&Hm3c19y6_B!J&k|kYuXiDHIDhm0sgh7TW%4ELTMt!C z*Rv|_8tCAcgJxT^?>?FFM3wgL>r}H0HtCqHPTmKaJr-oN&QALLd9iXE<{hB*aleN> zM$^q_r$~7)*MDa^^{8<9StZ6Z4=9fp+<5iIF-2H63pGzWT9RulyLV-0mTkJ`-mjP> zsJ~8n^~lp)^i@pKpm~+e63$snDkS8U1pX+4=ZK8jY zn>!ibc!(z3H1l-aQf{qMJ#5#Oo8E7|0kP`KN1~=MPAm}?$-fpZb3E1BW}%r6S+fR; zk>n?&ugRUsQ+!`s!5pm1Q@lvITioj(SnIC1_whg{bQ?Bb=yyy1Ckepn{ltFTS@A8m^g~>oOEL}9(&mGU7Skqf7Cu=)cYF=8OKbdy% z{-x}+8ydW^p5;Uk6v0SOg=yu+>`9Ia$1Uy=-@}!S)11D4qD30yD{#~VUCHmabI;s0 zrpYVvtd+0n0=q#4D_Yt8>1WlX_WX}fn4ViB8(Xz&b=zp1ztZ4DAZ|l`cnlM>L+;e+@UcNG+#~Zm1T05 zwx9LxFCn?J6?~AHRUpJ-YyB|a{i?>!=I8CyA5^N;W7j=ir(EsLpgmfi`m z4z!J%J3Llo0HYJ;e2`g6GU9w%`veb^3Ll7b0m05{vT!>HjR|9Ju5V|vB=97Ah8M4q zo!!C&5MF3(m5U$_X%8Q4LSfpId6b@O5GlD)^X3k^mbA2#_m6$NG_tPj-brX`U$H!u zmOH0BB`$9^c2#%t6K)=eK-jDv&&JbrusQ^WgYiKz_+4q9?I|rHqoPOv-F9m=WUDl> zUrnD6!*NOxW;H|$iC$!%v7kEj`qjg3n)~aVac&G9?2IL@$hG--u)nP}7PG&Yq)zwj z=w0xV5x>=&c9~^8z8N*yvEDJfuJ+!#PG!^X72{X@B!;FFZd9Smw`BSGurcf}=MyXy z&%ZxVp=f{I^$x9vRBT<`2F;;WmuBzD)^~yX^C7I(U)#yQ1_%ZT-7bHA_~P^1W}Ktk z`~nb(x!9gKl7Ie=w)K6R!avF;a&LIY`@8Gj&gXGX-UVTS8WZ1oEJah8efd{;LUzSI zIB%%&N26<94kW`h^zVo!+Bfir9OBId;2bw7=fr3&sGwXvCydCMvOzFyJJZAkokocaz%=? zHo9>^4GN75d1dI**L3(h)k4%a=>69lE?|$!qQKF!T!}SzNmdkCq|_*!eyRE4qIqeZ zD)R%E1@CqJCZD>YtHP4#V1W2KFFZjkRIVe%j1~M~&*@9B^C4FsZIOQFBZH6Dc&a5H z#3{Ll)%VG!4NB{mwwmsvu^XnMA%R2^5AizL=#?%{3wX7?qr@SwHwI@YY)db}Ve@y& z+mB3`knaayKFqyFs2X%|+HP!9&OxRb$cs0nAl!XZdcW!0ug>V}1~1(&@rt3(V@lKG zkdo!YcN@7fsg-W{lsC!%M-e{{o35dc2yACRMl{SdtCD1zXh%E@?QWY;`zWLF-F^Ll-N`r<)w(|3IfH@-r6V$S&U<%hqi+af9w-V_s6*+g>ZyaLPl(gT&FBuBa^$gt zJ%--#keTkHFx5Jl9-wsz!_GS4>G(D^uihDZcLuoCA2xdZRZK(n;Xhq#x|B3!z1K3Q~gviBE zI!v=OLGPH3ZYa*op4$va-CCB(5l zdXam3>WRxxl6%FO$9>J_*PrC06Pex+bd&2z7AU9q*;h(0uvm*1xg?^-%e?V|xE$C} z4MGdN4fb>EwOED(v75%-5x9J z)O3%$+!_gME&y2=o#Wa=U&St>uy9k}AT$y5$R(c+FZxZ0A)Dc(Sa9eswNvva;#oCf z%ubu`2h93RTqp&Bs2wF}<$@iRGB zF3Yb)v0+@8-6_9L68+11V-i3G+dg16Ug1q)iBo}%;$F_v!lAby3-3!FQsdnZV3vs5dPYTUY@uiqIT#v1J-5|V&y&fo zcj)1G(O*okPx319xh+)j_tac0Os3$efHU^|nzzw6ny#=9Orv}n!@P{gY7Mi`%{5AM zV`Y&iSxC|eUjNwRAGu{t)0*RbVf%%%M9<7qquDL=Um4iny-;=pA$Xm%Uq`EHzl+{8 zIf=3fOG9-o2G5&zH-_YgzSMtT%1EaXwTHj9w9&QYK0#gA<7L8|bLJDq&|ApI>Z^7i z>~hJXZ)p*@CUDh|#=c-(L}n#wI3o%JzWFoAl86J{9%7k`*u;1QG4~IgG|OFjVi*fo z!uOPmhMnOe-Tc5j6=(H}q%O|A2A-(1)$F>BXs?t>&xJlkYVo5AEe?7-b*(zP%761)W6bqGl5v@9q84$z zCjcKu=3+{2?Vw^RNobx@{m-N&CUgf1wfHl?-tt?F5qIo-s=exPZ}A&pbxkGej~d%< zPbbG?%I+i~2VJDQ&KwLb_X30u$9bz5sSoi69D6}=HEMfpa?(X&<1+LpF0rZ8Ca2%N zq+^PjggW2AvtyT?F|&h%Q68k)Nb=rq=X=tP5?%co5Bs}Fg=ur)Y+L4~hmHnS{qPFv ztE))q3x(5Jul9VV=ONo{Ny%j-e}g&r;GkQn!036=_Rro<7m#uNc)t@TtUxhbZC^R- z^CMGyL^lbV$Hw0xvVWV*ArxdeICG!szq`)=|Efv6y?2Y!SfPON*3f2iX7{`uR8t66 zCfZ%<+aSMl=3BmZ4fxnJ)?4Z=I9W_g#;mF*W=5uj5Ern>8;_(}pLqP*ctizp^y;Ex6@v)zKz{6P|0LaAidperPl5A3s-l-UCCItsf zNuGL^+!Y>L8+d~~D1{AfoZIY(l1*AVTWP0PpW)`De=BQT>Q41JZzyyAWx4nE#+z^B z9KStOWk`A9^qsG2^Y#+M*AB|$mZt+@a?DbO<2?HO`LR|y5A}+Ph$dFMtbL5YBoSE5! zty5>auQ`v%x{{3`wXNMHz4zLRT2MynbLXzj&8?k~q*1T9TDB`n5opzU*Xubq!RC}S z`VPI{6*jB5tue~1L@S(u6BgJ3cZ2@%jfH$TN(IH?-Q7s-66Mr;!Ys9(_T_^7pID6A znO%I2E_OJHpL<}@mhc`az)*dAuK(_#vt+G91X)|U5oh9MW={gDvXQWFK;!xgA8~7X z_=I%CS;DD3Pn*|M_jT0%()$SFbPF>PdAiXmpD>S{CzNdYjz)r0iD^0YoEmrNlFrwU zC_=3y&-g3<=E3`~qH!r-C5}(n*Dq+^e(QIr*%l+3y6Z3E5N@crr@H))PhW_BaP3_C z3zkil&CC@_?Gs|(wHPG4O$q;#cpN}GyAh}K9XjdJj?#uRtq zH>*^tE`ko}n|8jUajJM;I_>z?TZmj&duurQbJ^#Z*XmvNDp1Q|4j9wxFH*k_I%~?= z&-l8l#^PC(^a+qv>rGb3mOO1 zQ*C~V@d)Z`g>vuI4JYH!E-WfK9}AK(WoSJ;b9R~Tx0a_i%y)&!yErENfCxFAIb@cv&R z9j&x{HYQT4m7bx$B3t*jter6nlO%@OY-~tU&P6WxX%hZi_rP}6W7qy&|3_A#f3PbactHjDAJTco|JA>K{v*#2QG11~!_4OCP3fy; zX3?J>lj_VxE$w{}UEhYN=jq}1P^^aH-hNOfvv0mznZ@u7$T9;=D~?YV5@w;P^Y<(l zf%2dZJwk5rvwi1~7zSgZZp;z}?3jR?k(aKkt@V+xYF7zV=9S9!Eo?_G}ujf>;U>Sq{|T>eNkPGr9npv~v5eoDnOO zkI|-||MODVc?VmVcmHn9Fq`Kz>Cwl3!~T032oFND@K-gb|Kp=>5J(w`F+3dXNs7X6 zKEF94QsZ1aJKs;)r1?5UXL_!5$7Om!)Z5J?9ZZ`aTt>s^rfhES{MsoICekl{!k#51 z&S8=#8P(`Ct6ev@7aWNz@ zVgKkzteAKEnkn>at-Xs{)gO^@Y)J7zPIlLpyYURXM&yz-JC>$hI-gAv0SuQzC3GRyIh`>d+-f_wN{S52scmW zkKBgW!c6@tT_aTKCXDjWtufAf^0+FW!P}8SjlKp;S2N)PJH#KyIy@X|H<1sbU4nX} z9^vbBZqkQtv5-mKI(4ob^1z$sm?-y(W4x!2>{ddu=DYbs>fN6rh#Zl6|5!%hpm}Kl zVO1QjqkXIc$0Kv2MpKzUqv##RjlJA2{WY*MB(N2}b+{q>XuhXlXsPDh%vn-;b(+49 zR~3k=T}&$`Cc!402L;VINq2s#{`%)*S8H@(KbL>P55Q%17`KDILQl{OMDDbbWK9y? z+FLxy_{MJn%enQK?=6uUyJAUCTAK2b7aEDGAhGSWxo`0DdOUV}soK`I9zv%n;aTO+ zTEd~S5g$qnQyiD7zn+|{L~DO%u=|1)*Ci8mhk;`MZuR15LUk!%9io%j6O z>xGG9uL8Tgk*KrUHJWAD22KQ1Yv|BHMbeC-SsF+?zsLsRf;JuD86ZH;(n}4Tyu^vD z5NW@wYB$^d{wwVMLN>=@V!w|*T^v}?dd*_h|3JG|Td6?*=>ujB5)=H+p2*;R^jyuT z`FLRkRy*y&-~{fpTXAga41f{hjrLZAUT={=!BB~T{GP&7f74{^&863}WdQ1E%M!_i zd%1fedLXc))0z-K$k_PakL_Re>JpP0o9C1#v8KKhg-Li}y(?6NbWAyS`MSQy%XQ}eE z3uF$t+EG1pLlUsdCgKoTS05#soD?(a!Z9bfr9(i4{FRq*nwZ|2{{#E-=?1w*C?jfe}Se0 zwxWXxEsKz}Xg$7XZNr%=nL{)g9I~}`?@z-@e?h@psqc9BIqXNfcYsF(U8%U%lz^3r zcuC8b8V_0fUj>lYM?>-9745ODA&-4LRO-M&vDp7CIzc#Z-a&!8H*=ciMz5|aJ*&n! zrNxQ-2Cgh|#WhTVpZzk=JBozbf$RdnjoX2z?Zn*B0tmROp(LBHxfHxZBst1Su0lQ# z!2ga=@z%0lpH=Dx0Rxw<58{`wb5!KW;@)*uup~`^(6-hPY$6#e$Ulga^!F(N_ug!2 zjq#;UYgaPV+Mh9tS+MQ=Ms7lZ8j#Go`r8g|w1S?Ct1JgPx^!+3KvjUc!AHPt&G z+ls-3@9*^1IC*VZLnS$jGp8FH%QTLPJ5j?rm>5DA_J<9hK$qb$N9`?D_sg!c^EBAc z^-ePkj-F~;a?$kXCNc}pEJ3f{jYbgrF`Yn-p{E^Qm;ntAX|VuvP>>v*p_mS|s`~S9 zf4h77;A|YX4t1i)^5cAGXx{bb-w{yQiDRv}r2K3@h(B~imIM{qt@}#z4%OJ}&~k73 z=!fsoK~mCpdX*SeXOg^EGO&X(&4HFk*mrW=3Vph8RkV;(Bu*g~!ZSjZ0cSfKLL>=F zmG?sWMkVA6>k!Mfrt=>uJ;HglxaFsBs=9to@-X!K?bGS>Ih74G5f+o^P9#Z!n=Eks z)E73+l5Fg~x!zx1r82#h!p2+w+D`E`-=ZL%B~JI;D;Vh#oQk)IieoRlUV0q(b0$tu z%a6n4Vk2Q@qk zzci1q5FdPp9Q6MC4S1N9K{%hncT39~HSWofrS$BzQ-&2ucSCdi*`7|Zo+MK2+YLR~ znKOea?A`tgB}VS0TYXdaFC||#$5C~B!4=BPyD%Sr$pP!N#0TdthoG6~ifNihL*Hv2 z&-YBxdQg4j&8;>9HrD{X5>SF>xE>LOfq=9Oa(gfig$VIXwgqK000q3*PGI2w`z*XCAqWzEnzkWa=xZUkD_`-P_gv<~qbd zR1<|!S8lq}X?~}i&Vc5+9jPEZTWZBaRB=$)#%3yzHhn~mc>+`$5hb&5icjcWDTOf3|FG^B4snoP(E`%jj={4>O$_X<4=L|H`nnSuIur|XGrdz|KXN3$ zt)&kngnvb8{vJ@)5VxWIR3;QB7m&*!E9HRyC9(vs6V}#>rbzYKN#oNOO^;3)p>{tJ!qQrCQeG);Z!k`CB8sIa$l00 z-7@zK;b12f2f$ML@->Rl%6(@AA(6akjACAuxJ3hCfaG_As?BNXp9y{-W^(iKG^(=d z^U6I#e`~im&Dya_8Q4iVOrcXFj0F2s@kHicHUk-uEG_HsG8i9V$w6lsWD%qF5kK2( zhD1%(mGYwxeA(Rq@ySzvu02vf&y;0GB|4j1i6>QyM}T$47VPY%##trZYXoDHUP(wf zT3)Dq@eGcZk}0ak>SNeB?NamW9g|T!9UzdQQwaPc9t7d?{$4dwLFcTT#HDZf?Ty(; z4fM z7N+Yh@S)+0=FE3xDOJ(+6~3Mk>>h4#K9?B0jzb{lP{63Z(Bo=9`hj8TOxoiqYQCRT zt3+F+Ia?Bz&lN_oL>>8y&yM~`>$5?Q`!1H#86XKcG2%?%V%RWmi8~FumNE~~3Udb1 zFMP%EBUJ}$Wi29hHy$2l^oh`uIvl=GD()HvzqTD7fqijr2{u!$^u2t-rQ(+N;g&I% z1xIs%x*ZFW%>@Qr-A4M4_;a<0TH0~)j-oHl-$>FPAb)mVGX*B=3pILUp{rP@UJBQP z&Z0yQzRevV)iOJqa5Pl^>*ut3!Yb(;siSsk?Qfs<=c=JE4!+9rXl+?<)7t|Yw@95? zG=U)AtS#Z!Dhms6tram!9aYFrZ-o?E{p`IXYEGHv*2TA5?{A)~j5Q}t<(Sb^WVOFJ zMo5RsQAj@=adVjMoa+8?Rdi66*Dw@gsJB4h$wtA0lx(i6S}VBc0IfIgTnI^y9ra=S zcjKY%3k7>&4u-;>k*>UF1-WIpZ|)85%ns~^`l!7$I_T2+5MnDQ4YVPb~v99mFY3}eXj*FsFvyAzZa^G4!54j{wjjD#(hsj z?re+D5IUFaB;C-_nK>bB$@nG<^V|MTMMpL#8%+v6l;AQ~`DYXtb-cZQ=^*)h;+rTz`1rj%~^iPqvnO!`{!)AU3`LaF- z5a>Azz82|#ySosM2%ZmeORD`Jk9qzba|@#>B2B;QPUcKcwiFI733IQ~1bCHbEDs<( zc({oZ$^n$Kmy=g#d3ZI3+DWN;2&=}aYJpYxn z3j2Fjdn_~nuu~oUEG(f_DbfKpR`z++w%tB3ZQd{MFKV;JUoCy6()^agE$>aVn!V^e z730iJ&F&?&ym%w&Lh~@@xY8!6JQpggN+1SVHtqURU~) z^R}D|v#C5>ZiZtm^iu8|qz0xEjz#W)Pp=QmEWWqI2Irx6lKB-IGkhU!a6z4}6`*lqbX;I-InwqQJi?U|2R_}s0t@qvRSx`UhLM}z5i6@k9Q zEw!~Z-{W~qWah^~oU%6=IJqg|i5ZfoX)1%5)Sy@g8&*=Gt(B_Dc3?aQ_aYIUw~8|| zMBO=CHzEC|AF^?$IeEL%g_D86+zx9*2(2*l;r1fa^T#u>JUvu_Mck6*Q<(9z&r0yE z&7ZUy(ESk6l-;#?Q+<2Pd8L<{{KhYW#k{~@r%1O+#Q*RumvNoms~g2!Z6s_1xYA6@ z=5XS6PqnMAnlg!k%vlYhomCY9lR% zWg{V@2H{W5?zKSpOF*^_u@^&U!7vrA5#tWIW~>EqY_XXgtk@#WK)pp8f&ZRJE{J>O zbU7Lp=$GfKH&=pljG?2%q;VCZp*L8A-YeRqEPb}8+ql!v@a{J7&KN5$CH0@BH~3oe z?4!}IfW4Q+QZ>$5GdQg|*~7huc2ffS)h;ZHy>H<>zhzH%1o`w1yjMR?)cb}UPdEZA zTitrGh5!L}|0^ANg8(w3soX@>Qh3dXdkcQmLzWEHfl+cU>1mN*oKNe@+m{Jh^T>e)(v;V0WvrtD^ddR>{gh92BY z$gi@Ff^bvL*0ruDQm1+okl(}5apsUZO!)7#@89#mdv;3@Ru4%wOj z-R|`x!f_^dFn0N*NuhV(AT~ta9{*MUTZ=o?nm$w$4*5eTX5Lv!>W#q>b?VZ?J;!O< z4=7n0;gZ{J)y0OTew*LRn}R9QcDYk{o2oBEXTrt)=;FLHB0^{*ZAk|Az)Z;AWPDk3 z1MJB;lt@2+31VwFJ#=V!(c%w2M%%h4rFq`B(+Zv+!)AxcJ|xq5XyOhj~pbs__WAy^(Ud^Fqh zG&sbdVmGW80p$V`pF02GX7AHL&|;9B#6My7)D7ftY#r{1lh6@GIATy|!9x2O!DT}C zkFPGW3SU+33S&n+ckcGu*nkV&MgW6_&cnSJ{_C4ReTU1P&_w_YsBVDk+?h5krFw#g z99Nj8qY5!_R^ZbvgA+Az8*J6{C{uiH zb||kXvt$afGP~Tj_Od;EXpl@`7uNxDST{v0!482cX|vakeRch%778oVKQ0U3ok-YT z>~9s64a;i$VFUGxcUWko0@kW@#iKv>UgD;SY5#k%KzBa)9zx`1y#OY!OMSTt$pF0< zF+q3y0>*1aZr=EZ?(vSP{nRa^W{B^1Ztg+$hkQ`$&U|hH);mN|kRdMrvdM6wN(SV(OpjU5 zCCn4)VGROU>?+Wj;Xfu&}H<=M7amUuD_Lq+98 zE)H+kdFZf~yV>g=B|cR5fOiL|r#`%U$U!1_wP2^mp3%zxkIg1ZAd3V=U?c`Ld&+C? z2|to+(DY4Xf|UT3SMss&{wbk?a93i+*~RDHnaZ2{$Lbv`iZfV3LhN;B`6r>I*zEw* zcPCMeM5ENoW{C&Tb{}KOYsuO^sRKRmnpz#CO8M>^690~}-8vV9%K;C`7yV7>9GpKFMki0okE5eB{iIIh5xLlId^oGp2d@$O zhY=$|O`jf9_H6E1c)ee12WPFOsqvraTclLX7t+86(eX)nO7ZeIh@E`A)>9117{)J} z&UEes509#lbrz7a{upEOsrcH)%(HTvW75dG;;B3CSuzwB7*BK`oJy(z_W?RzP0rik zFND~(-(e%aD|LxO+`O!T6Jo3m)=v_w-8q#3v|hm@>oNVS2|N(oRcy@Su$344E70cm zb_wcxwHVD9T`jzqP675m)7i};YWD1_$Absh@X8ARNuEG<|EOB?swUzexG<*a{(UN3 zR=z=o8aNcMcfAo%<8jR)Frco+1dwlfr#{~UisRQeU!jvB0CA-EuqRuP_(23R4>Z^2 z0n!hO0^DVX?hPcSY51LK#pb}HV?-$9Z!R z=!l*kk0;hcmqSRO-)bFy)En);d{rc0G3J2e3-$(15NF)y%D8$BG>{zWl+no^Q4We> z18r7=3lp11<2WzN8whgq;fqafLg;TPRq^{@JNja7O^6j zRhPZxQ|H;6_R*>cHEi5q=u5V<_`pwbe4BH99l*a>#`$-N=+?8iCh=;2Igl-I4GTPv zzuhv3t-m*(D8Ub^=S+5glj>*Ep8vrP69 zy{e9&iSN(x(MS3lom5{G(nF?b&Ca93rB@)A09Jm4dMQEA>g6^*mz<7mwb@&YG!TKH z&yx6Ra*Z}o4Zm5bCP9g%K%gDB<&62n%KSg(MpeJ<-ezI75MHRl)9*|pM4o|AtsnLZ|7X^cPi(tB~Jx^lI|(gXQC_SrUOmwvihvsaj1fl2G-DeXudT zu=8C=kIz5lQGcJ>mJB({@rkQUdxL1BtizplvbIZLMiE|Re1rS#y?gnMdxS-q1*6jw znoPlIDWL0BDa5+@9Gpy>TT!x`^^C^(O^7x0?JE=gR|(u)QdCmYdTf=QL)P{X0g(hf z$s{w0+Z}D(_!X?U6#^2YR}uunKAGOfaLm4>fqp* zOQ5>SGmCNw8za|=$ha#$^e%wUs;7O?hsQ^vx#C&=(ov6W_HqI=Y9K!E2*&5A46>m@ zH5bdV1O=&rvNB)oBYbTL7`mOJ>qXZy1{%FEnO#wfUvQXQ^b;aZfjEcO0w;WT3HdRZ ztyj=91f5((5*j+y`r_{a;qte(aX&5g!sO1EJh2Fok@%C&lTUAW_AG+Q$F3NT71D&B$K)M?Q ziJ`kw0i~oQhVE{p1VL1~1r!O9MmnTXx?4(+?v{pgk8AJu-DjWotPksx`h%J0x$o=x zCyD?Ts=M_>d(-w22rpBfNqnSjKnE*GVAbJi6IF&{&0n}%CEF`z%|3?z{-GGv&cA+0 zp>wCLgvVzR%01|m0)nwO%4G>tfz)(E1Z%aYP_110hh`W;v&18x^}*?{;lWy01Ln#K z^SN29ED4Xb9APorn2l#MdQ3hcbWk^i`$+DXkDq{Yp)yL9YFuHJ0lcMG=ZZZaCQPpS zQ#&|9U6Dn%@?G+y+HOdPGUc3TaCeGcQP7+y$`ZOSKZWld=ZaY zo&3X-8f(>v!~IwLK57K=%fr|5jqg9aWF0gh3}!K~K?)D# z*h5*{vKgExzRGa9P28I|Vr&zx=AL4Em`)P76*T&&9c{v(VZ zbIX3(H^dlg%OV7}GT!_gstikG~ITstnt8o07S#GO;&AP*{Msp;DNutSJKD{_g zsYw=6h&4n3fdXWUfa1RmL=?uoU0K! z9i;AFL^qHZsRZRL(gH(hm7})NKIx4C42vQfIZL|hdM{iZ2=MknW?mF_xJ}@CkaHg( zuQJw!YcP*Da}zHodhM(O$44W##s*{4re{)6JE-N1HJQ}%-3Nf<8rYwvX>%%)*y6jU zTO#*jX1F5m2a?KyD24yy8Axk|;AljS)T{R)y_X4!<9x@manQ9UNOpn67&|~SriA8Y zTPnZ^0=T{ZFxQ(B6|(}TFTx>KMh_#)Bd5M-5x|-Tr7!B0AyyhTfu6_HXyo&?O_Rc@ z>yQVL+<-3+_pr}8ZiCZS>Q8j=&1z$*7Vx&6nv3n6fh1m;NoWM7oi_|0GAU;RD?X0h zD>*UdDdq_m?X0O&!cmKKH<74Qyqa)$F52UZn=hd+W?e;(rxqfSnNTrbheqYDdUwwa zIPe_v1RZ_wsP9t*_`>?6!c!GF3D5*vD|sw&u1tWsAGobpkQ?|D3OZX-AEFZ){rY*>`n7kD4T8Gi7?u=_Mi z-Ja(xPxSqZlQZ(22NwnLEXmVx{b}UUFQfX)R~|MTpz|Qn(_OLeW~fGQ4p!yzyxJA&nxsds=0eo_Rao}*0+|DqN(U)M zZ|h6s)$eZzqnTxnr%Zw#&DFUgQbPdRfYmh`gaFnNPM_})1fkW^PKcb5Bpvag6kODQ zHlHI=RJ5az_p>)+Oj87f>d40fKjvq$X6;_w_q|wNaHW2;(>dZPv-Zi?=wBmZCI;9` z&e3tm=%j8=5)uHA-gmIn!E8I4>$W>1&^7ro{$&XFpN9Q zWS^yz84&|jB%8zvLYb7p(jP6l1U{) zT7d!B(=}`D$fqs_{Rq(B&$M|hdzl<(Ym&sg_wrBRnRnOgQV8ov$s0`L<4~z)uxIP| zvZ;Rx2APSS<%%mH5>6A)I0Ysx&4?9UKflFeGk&~SU+XjanP#Cjn~4AP0}slVxu)~^ z8acTjZ_iJnjyodur^mg4rEpwI7C;tEUG>BL zYnL6!_NG`I>(;&wspS3p-wO0cejE`Ce)nWA^#( zB!R7ZQ^p{r**yu>MoQ%!gsKjLy-{mX9fdh*ew*$O{9rBLHc$5F(**1-KnNAD=ax2t zKlvU*s?>R6Uq+~JK+V_)pI#OJ3F2l$ZyutFF*pKK?FeeYOcZ8Y+w@&@)E0@e;G$pi7;2dPMW7Tx$4 zCu2`7K?2jDtiQRVSg5u{$;n*BIk z5|Iw>M`DV8XD^>n4VX;3v4_gYf#l0nAna>$%15w{^;%XH$WOJ4bkr<=gUCI0iTMW4 z1VBL*5oIT1O@#$Mz~}Bpk#`0uSQPy08I*~->;;{%5FcTKLQK6<*&lcquGJjpnY@M z0fd^a;ZO+Qgf6Z6&gwu2C*YaZXVol1BeNBeqUBfU{&{X7c2w>)4n3CKK`prnnL&VS zAB+HT)ySu|%D*E~Lv(+DcS~D6qLVun96*IcAgarG|A4j`Jo4xYEbER^~bT~L-6pYHDn%U%rN(EWIGb|D{vN*7}1L7wZem;*RBdd z)ET5xp$2&4*`JVGK#n*O280PZ_12MIDVAxD5WIuoI^5|41$0#S8Q>V$I9+OR#UZ*b zmnzJlCp~xhoeEyAI8dM?hR!8TpJmY#&koZ=!|X}n&g?}BF_+yrPzBT|tB}*&@OsQP z?^I4Q#-cw)E-Oe_@N-hezJz9lcj5$+v#KPkmSJ8=!__M-ZkJjmK5fpAepWdZSl~0H zUC8|R;r|q1m0$0Mx*?;CLeCghy{|m+bUf#C!S^uJ5c8o{Q2CB(1>$4S20HrNMJqtfEJ99T*zB)w zFH0w1Dw9PO=FYE$T?E3e>GWeE-I%4g>k5vTlkbs2KefiRi!xyj)D9bN1EPNXC7S9> znG#&P)Yxy{`*ypiOqgw6Huqm!PSXywN}ewwmz2xkVl@xE5`WJNc`q9k0cH(}Habk7 zQV_+Zt!@s+L|h^iG+8sjv5v}4fr$bwB@@Pc%a@-%sbiP7UxnH8#JpaQv6mea(t;o0 z7Lw0dgP4mGDI&0x0<&`Dm*1R7TGb932xHW$=9 z!%c3qLnVPHxCB&Kc9AJ}#reMFc*kF7~ff}3! zZ> z^^QZj`}n|0T{`j%K5T)lMyIaje!QkuqM+aGUq9Je2Lvw5q?nX*8%UbIqV&Q)-=gtEHNSu^Af#{){I}+3GnTt3E&I$ozDE;~8m>EKTHa@^Q z=NHIC4S**$lnU=^Sud}(u4ea#Cm{LJ!7i(HNb<5L4K$7HO}4uk`AC~!2e-Q)1d{88 zBMD(hVzjxNKX<3bXx@u?(UnoR_s$*ersi&R@MOa$DnwXO?`ppFG|h#EKZ*C^;k0Xc zO#PrI($nIO^5HWSM0k{OPW|oAo8>{z*3&?j-Ih6VCP3_cqTX`7hw}+eL)s-f1`FQ( zD0RJF2f8ZP4AF1h>U9l&-HbiASo#i)7cqMLhIp9}Tph*qynP-RJMF00uWXq#uLtD$ zPJkG$2jszIbOj+qxwT-VlLUl7>0KN>mQNJLy^}2I;a4~TLh8awV;m?0r3ST5B@8dy zg+UQP00w@@@?s2gS`;`_Re+3u0p#9#3P#DAQh&JANDn?vMG9?ieg={P$R+%$uu#%m zvPe)}iOEi$%d}BzhQP^72?WT5b#0JBP1?y4A?rK}_Xc`~c>;SA+1Q22+$gF!Vi{2? zf>}Jld1Erim*)DuEl^nMV}K7Tn)~r0`Fmsnx;pMiB6MG@qSnQ9ZmdY)ay1oCN+C`) zAXe$U(Mn(4>rq2=&2l;{h&KTCQ=fGzrZ@>S0CyuYg_4kqRz`1=5JiHV>e zfnq~A42pUI@Xnsb!<$58duxiYv(`Wo&{;dY4V&Twg&Kk9*O_?^z^Rl7Y-1Ev8ZJ-Q zL^Iq0fIR4#{{|L=-P7uMZ)4QZui7~`Kny1HrG7t5qA%CH(%=c#?(kXi1slWj~Kh)XOPxVvf7c!y-WW5!=?iYg2oPtg*FGy7@P)u-eC-o5}10h?!%c5xc z-qp}qkIOPmFG*jKhm(d9Amvr2mVP?x^Dorzjon9G*=iFQTs8)+Fpr74*+2<`aw!LS zZmx#%)p-ZrcWy=gfT$;zR(!7BZNEfMn1AGcPLDcXx(U<=x?t}2V_&jcVa9~u;_*?1 z;}d<=NDpZjNqd}CDWv!-WE_|yG}7N>f#gY2Sbgr#H?(2)I4zNRMh{*kJ>eBf?RfAomfzpTRRW*v zI{sC^sYLh#1$XgoWgyHr&G2DaA|`7j-AI46=2K^FNNQ){Hq$7<?6qpDjkdDYnIMG=Vu*w3n`n7 zetLnoYB2Ba5KLqbV+!>`7aGp|v~7B2L`PG*`_F7&%dU!^!8FVWxfB3k%NB(6PTx|m zbQQfkj`;+MSx(!A-KSXT7vKAF=e*C+nj<>peAjYzJ0v18sulX10s}>M7{&X4|HIg; z(sO;SSy=VCbbo$Z?T<&i14~0?!q>^;VszeLH9z0?`?vV6id7hcZjeGYC)mtQnmOb( z)X1Q&6HE#_TiK_}H(C{DYZy^FfLor0ysx2$vJ4})lFep)s1m8M95I0$FNY>nm|qYf zyUY}(A}{!vZVh>_5EkaA-7j+EtoLv3<79pr2{HiE7E9*`teIq64hc2`;a%n4Q^R5 zYC_xGSkvs7-SQ1)nl2RTU+wUC!*5=Wx@Dfy_e9O<=dow$8=%td-)WHK7u8Td45>di zR}@eULnAX3vr~7Gu+r|Ph99tmMG!!cY)yji<$hUe6qb_iCv08h3C3i209!<-p2pvm z5faFagI0k&@6Q5)5J`S^Y3)vj9GnBWat4-r!BSM{F7DUot^ty9sAL$n-VvV`^@LeI zw*188Vt^nYd_O#RAzfRS9|19s!Gt9my=4a{*dNQW*FEg!ABN$s zPB;&p6{m5%h{8O)t>zOj2x;E|m7R|lJAK_Oj{T!T=nP!UW*K&+1x?j;`=(lKRkL|C z6vd3sqoLeZClJL#Vw!J3R^P#5i3yGr{EUJ3n8)kjr&g zx|?38dJ!i&TG`y}`&}U1Jxzo58auU3m_Z?JYc)AOjEFsiurJVci%0RgZZKf-= z5EsQ%gMTMR*iXZsylmt2g<-!i8BFTk&)?R2gs?6h6MLo$-=jcTtR{Lk#4p{)YA%X| zLu@S{d{|5-#x6PC@2NHy)+4lt;>nX2D;Tbf*=*X@!Xhj^eJ_sa`rVC-p)>}|YTiL! zmy{q@_u5s*^ScF~~V?>=UhFTAZz7MTcLnyvV(C}%M&XqwI zLor)^+78_K9dZW>4!zWdQQZUyNg_!w{ z^&YlqkhpWkEYU~oKYV4_v(k0eb%AHU$Z6bLoQ3ZN-V0dh{*N!L%2wORUJwFJO$0N` z2TU)J`Y$jF7f|d{TRy{u&pJszWU!6s^>lpp^f?Q%VgIhAVDMMX&GykE>mmG1T^-p@ z>AXl|UT>iGL8i2a=hv|yMOy!K*Jf`=B7|D&wDiMn|jeSW54uhTnbIR4H?{?wx>tDAdCvCAm zC_tAy!#wPB(-1SR?ntfZ6ARVgtlw!Eu#XDCZ;)jjaYu(^CDCHr-d-uwb|4vJ>Z6do z0Dodf(-4|EUzDf9QpWG*bmrFQD!NDh)z_y(+~^9Gy0^H7CrUJ3-~3W}vVUPTM+xue zH}A5%M0yEI&s=41MGEg#UIqRTbI-``G>F^}0Rp)AI|w2As|Prukznapo3fF~f%t#3 zNV-jql@BiOLLuwr`av8lzLh#k_($F!{H*X4e$@q4H|r5ll?Ydq7?A}4IjV! zoW$ng9_`)-A4@C)?a0abu;bOl?{DruIOI&~N`Rc1UDq)oMM|)=s(WEZ$*8BlPSo`f#c|{i&ftHo=3YrAVK#oo6CbqP?AbJbbZ9k)*~Rk<}Lr z*q>C0oXBSoJie9oP^U~q%zwXMaC5vd+Tyr}4rG?agF#}uJ??yxM!KULhni4P?j^t_ z&|7-h*uB8Z%YmfIfkF4O+M2;2G3K{)qf0q&pmtbI_nKJ}C@FYDf`j<@5x?jYwi+l} zryslC^E{0btaz!I%tQ{NPjR%txHPphuk#qqk#JUD{qqo_Dv-b-T-|&zTS#&E*^;-n zw+$QChTs#VA%s8pvVzju8c{{Jb+q*I*-VJ{TFOz4-JP?m^2L9iVx}45C zScVDZ;Ym&%v2(PnJ{@{seB5;-am)W!k$~uxZ+UQ(l?=2udK``ztMa z7(miVG6AFFMo0?&jLIc&Z-SU@56c^{z-?dLf-hACEI=Mo9986GWclz!5qGQkW-w?p zkbP$Jkd%Wu0o0Ni^h(Sap}vcjRkls%w~a?ZL9x+rN@9Pu0z^q8TZxMQJm731sIWc7 zrCR;I#b#MaHKhsg&}07dVqjz8!YZu>;`wbyZ323MOvvJNYXS>*!zyIrs@C}z7df9* z;_3F(c6%}?Xq@nhq89T?1UQEMQ~#4z^k9f808be2ZuWydgBuBpS`UM8gi^Y<&UJYO zAQx$xXmyC3_zZ~`I%B=C1rWiD%0z_@dj>+cf7Uu@f^|r?v9YlVPI}4*^41dpfMfe^ z9pEXwpJYOrfC1ZWxif0fn%wuFGsx|+D-^!5aW!O3y1M#d`Do+%iLWc8dULaK#fJ-tO(WUR+w?e{F=_?oKwmG}hhN-GM>F-DLmu@)kqTQ2zjp_=sz+t>^B{GYUb6 zeAx0m805aZ9e^IQH%;_D({^SX3$u*YL14;49lnUUMLrO;j^wUCFllc5NK252&_#o$ z)51+_VVYK^s(ZAO919BzSgLCmriO&KQHB40|EDnFfkA#x+^#Mno_2bSHkh8`?~P^y z%_9HPsiK}#uIiQUElyw))$s-?trXhatRew?kM{ql;Y47Dgy8)ti|;2N?Tud5>d3%G zgUyRKKS~=fu*eXq952+?OryBt))$sOBAendbs<&Dteg?5kgRu%JHN0D1;$2d}OFHZgtvm3Im(u;PRnis9wF^XIFZoVaR;bOz*t~EVrZR497l=9O2M|qWpDGI*HexljsJqc8=FRz z*GW82dB(V%(CjQ21GZKg!f~TXXs%} ziliHR>-w6z(;j_C=9^F`wUmT7XA615YxoJ8aNY>TVDm-Zmm0xo8PHpE2rNK7n138y>Ym(EnZ1z4>o+`mi5_^o|G#-); z$Q#=Wd8When35k~L}?8lhGdrUguif(Ub>T_?CNM)6FmPZ9_WKOjw2w;`Y5S->K+g@ z3O=jI$uEf3fS_=MALIgfJ5GEEps4`Wwd+l(C&Aq^pb)TIK}rQ3C65cW3swMIBzkY@ zF5mm5#&}F3uNLHCac|Ui#Q#1`1n?RDQd5z8>5$N9o2;%zoC~ z&2y^B{$kO$!;E@--lL4X6`TFK;lqyvbd}Xn1%A&m zkCDdTA0(r+*|g-jc8mz$Rh& z8yDmQ3B|zH=|PKxyn=8*D1r&LY+?t|Y_`U}#3yk3(cgszpAtLZHJrU2dFwl^280i%h(haP(}JJUSwM*C^TLcR85V$4{()wgWH z{+^8L`<~m16RQ`iH%H@j(b*U74`b;x`Cd3kHHAN`RAiSg$rRGrpE!wY;xDZ14;GUq z*8DTLW5Dtva+_@>(+Fg|6%I|^-0Hsvvk?8?dC^P;ENc+iH}{!6s8aycYcp~Kn5SIX zFf0RfE#OMr6}IA1CnpG&DY6`I`t(8{T#A;h!BB%wcs4TZ>s!2D zr(4gWrWYF?>XsIFZH?r-ZuB{n?aE>J*JQNmi9)9O-J4=~$!Xl$W{L|L&YSm?^I6oJ zbCYE)i_P&YQB!Us{>&#EuHsK2p+rSbK}BOm(Q5NIG&OYpRJ!cH|-$SunNsXBsMq$*#ASEeY+}12CqVM%&g8|_S z6ta%|y9a4fDS5tOG~Q=fxbDpFyhTN7t?RdW9 zo)jM!FcXFibEKGvy{^BJ%{Ass6BizZglY@BQw=$v?u=-*`|Q#M;EZHhJi7lVyo#-Q znXJZ_xD~OIzg_8L13dZYuQ$H^kL13+iShPRdym|j$ey8FhG(81L_V4m<)!~l*;?R# zuEH!T!hem$C!&gQ1Ht@4PYU`-+2fd@?G@UQw_GJ#o8|`{$6}}DFO3XrE)#qk4>Y?; z)Mywa$;bK*ORzg4>EmDi=~aF$S{E4Yr6{(KhEG;zsXF=a8x)5E`_mGnlMxwKLZO`y z;#=`88kbuD(ni?2W5C0S(+X1K2L+#I`GlN<17k%F-Dxvmey z{jT3jO$iw%%Vyr6DlRs?OVHNCYB}WasO{y1!QD$y{Nri8$op&-kl+oZejxZDj_u#T z9sHH0&q>;vG2f&LUF&8sZ>RN-0%nFp5G3AoAKuSpXQj*IL2a*5_SQl<{qeTR0U4yT zF=h{P{Bt7oFa3SB=cF!y4f&jMXsGcuW?dPq#yNktlK=gr<%2Odb)h&U77hSI_nPtZ zbFGymp=qV_3(ZHuTGYsm@uQG8|0?-7EIuq(dkF$CoM((AAJV2qC{p;oB~z%ED_BMC zga*e>N=240`#vN*x7hyuXlCXoI1p+^^B!A?uPb742WhPQD zZ9;;RsFFSCi843ar79K+9dt-~Og!0s<^C<@p-bX}4Ftx^(^=cy#5ZdQL7r|qmNS?o zSvH`_m^Zx^)4)QrNFmR;+-OE2W0!o3xc$j`dH&zGz^84phS=4?Wc|FT4NKMbp>S*% zESuGSJ#sR+HJ?z1i3wD?Z;oXZK(Q(LDMI}27q8(dvstMAK3*Nni$WU~Ui_l;#d9}x z1A;SY(zZfNz$EY4P+eL^XNrWAEjgxmGH&0O&X>+#_FREPmFj`5CQCxm>nVLCoWWmT z6@3rEzG?Y(HNmv=Fvd~e#v#RcONXrl+XqQglSPH2`eDkbC@mrUtJLWFFmZ`b+uTem zq?(^Gay?`NXS5dsrtMGkUr&`WYw$}A6H~8dza*16oGOQjcfSL6V*K#N^C3j|5;F4i zCpCL$!b=$@^TNf{RW3O4)^qQ+4uhyjH+84cG)Sp_QOOk&m-ft|W2MDzQ0=biE!AI7+Iz~`%cBThu1o=(;MD(Xn2?b zO<3bGw*0?d^9E@D_694d*P{>YpQ{$o@Q*jHxs1wCAFjR*kAG$MfBcOVrq)Hu)4oo7 zTI#Z|E=w8ZH!I(36q090HG~)_K`HSRQE6v2`{Rjwy9@V^vLix`P_?QCw;cd|IfKWrb zq|VwMi0TPdGSflS4wY`v&TOxFrWDyf?m1Qwt9}>xO@qqrv?s3kG4tEZtlHm#trg?8?|uL;1Dx{;gU`L#*__#_dXDA@L2CfJ>&@x&u6&*IQ zMc#>mZOfr&G-KDYK_+qs+U0TG_hZv<2cJ7X&XVm6!1WwD{3hwLD1G4kI-3C@I(Y=5 zVLBRX;Lgs@k52YxO^p-OwzcCcza{H8N9UNS!gU9!=zS}$y7LqWBYUieks>_Wc}1gk zjYZVL|2S|)+3O}!5I;r~i&!q4L)}&nL>=QCs!g;(==~Mh{#2I9w}Y13)2D~W$CdsA z&I^qq=iH&$W;%a&*+wf_eiZ4Y{e5mQgvNoEw{C!`AVM2N>jyvzGY*ZoUW@))O#0q2 z&`F3W&;g1wKG{;^rUr|l-;Nhu_@q&IBj)L(%27u@K1<&=0#2V4!K6o03O$*rvSk#h zv>p?Dt}$ZxJK-)+~X2 z8Ub;#85idtUg5<~R4Q%rl>CV)E>~28-tCMwz3>MAqRle4)HU^@$-mLKM#an36cYPbjS9}iyFNhA&v?s3~V2;XulnUaa6m*CMRaBef1qs(c0n_$E(TJrL&OoaHTKOJT zSVu`g+*gMUdfs!st8)0Mi2y+eIK-Xh8xZcvfMTx_1I-HcU@jbM&&YhTggRil?*lre z(0#-6$LWHc(D1j(5SYR{k|gjhph^AKKiiv6Fbl)(e9#J4@a0JKvAeqe7t$>-F~9VL z&1q=0As}5MGmhfTOx9W|Nq;@9=);S!A$EUE@4MRog!IcoIYkjXkfy$o-7_eu0O~|( zag*3CDr=4h+af;v!R+5tq~AUl(WMA*F-u@FyEKI}`%BaPcmQ1HK=;tQsFYLs>K;r= zLYO%W$?Y+aOs({BwA?!^ zUUrPf9FL~4HSm#uHRCbKz6YY?nZ_S?OP5{o>8>CQh3daoYYyYK70o4RUVjMUS}7#tiKvCP4cy-({g97L%!x zZZ{i>Q-yc5GQLi;A|zG!PzzKH_Bb4dJGKZYeXA&{Nok$@`m_=!V?zvwCWQ5K*3 z=Q8L=jU0ANAx-t=H&f^8-5LUx5@dr`rO!#$E2MuU>L#Vbqm{%7L~SyNXh#S^3sbmD z1^9H<-{gbg%n%He0I4o}b6}MY3JU=uXmY^#F>Eq+zv=AbN^g?NyPKRX@B*p;W}Xoj zR-nZ)#wF)Eug~Xe8|Nnfs;UX703Ti4N44CnGEMG!7rFkF>;bSMf?u(`Fdw2SXkyZ{ znf?ec&$NtzXS;WH+ZIK5s$+VKZl}c>r2(L0ndR(>vwKvKh3cn1V(vwXF0)jd&}g1q zK~Fo4DFH#Sm0ny<5>Q`lF0ttg+kUk#c1jwZY3l{VXh0FatVJ}sQ^xw+I>{@SvMM|E z0Rcf*7a?EY^}6VQp#4`Mh-y|~GS^GN*UhzdyNSlGN_91LrN|3EcU@;;RcMt$H( z452;bAj-@!e})KMUu=D;A*eY50qbgN%iXRs*kOJP?+e`?dIv-k5Tr3wIn5g^To1J{ z`QG1NR_N?mczR-h6#3KR_p?qv#p%uj*kPO3-qov=())h25H^O$vil&JM*igdP(cHl zI#=(eyxaTP0zQ?@^BXKIJr3saPNy$zDN2%|cx#d!S5?@DoHsegVixMPI;DrlFK)N) zpPvpe@>&~8O-)~3m=nWbXt0@Dt2}#$NT^VzF=kp_hxb!Q*Qhp|Bh%=tTgRD*kEP`U z?^xLr-Oay-l2m%b};(CUDs#$M$fhyFQ<_;S}vc*pwxVC;%%-Xhw*6-buw(9%+ zrj%zq3$8{SxpZMHS~nwr_Dk%TbOm5;CW@!qixgrY6IwDTGQj(+uK0skr$G2*r^zqT zLUTx4<+qgjPW3UQZr+%y{&NYO?Fk*Av)}+ZYw?krT7A!*Zi_IX}l$c4JC3Fz{p}Zs%vE(l@fD>Nok*KvHJ`+JylcM5ywh z&0=dfOHNdObFRMf;}<{*0EnBn-tV+f_AOh+G62OZ0&o0`rU|;b1WdET6!8v?To=1(i{@PIXavE}ra=WlleF&;e_~`88^Cq1Pg^iCc*OO;!ozYuDj5!9a2}S0AFRS>2`7dK}oQClW0!|gfZ2=moK&tEf>R8EeOalaZ(z5X&YpRvX zQ0lqnm&a^MF*LZ%e)da}puq0Q(OOTzFQ40s{!5>@!)*iP&@iGy@!R#F+x4Ws>{+$l z1SqT9L)j-zY_A1nziiJ66R&rjgDU6HVOX)QugO%$%ZIl?Kit!cpu7FM9>uJ5rX&HE&=%JDnxOX+$2iR}tRfzc-3fC?r!x znSKCj)C&riOW6p||BP(u#R)*yf;^ZVJRb5!okrPBm6i-2wA@{_G)Nb{Zw|vy2A#x2 z>=1grT6EM_y~KMD`&v#XpZlpoFmH9}c3%H5zB`Nw+K`O6c9?H?=C!|2a%HB*ytBN$ zT|`K6ZA9;R6eY9}8+5a6a`_pW&F{H2KGNk93BcT~^5r6MYkXSBQf|&j+p-jR(j^gO z-)MrnIbz^;VVMl<`gR7CcCPq0F2D9_S*@%2^d~vqO9Z0P7eP!gR{B1u?Pbi}|4pU= z$msvMPVYC<8-t*X^Yilu>WBh>OENm-yFf6@Bf23zB!UE35qSeuZLrLGp@Y^;;rX@mf>_rnK2a;j>G>u5Fr53kxuJ90AM1R^YQj?Gfi7 zC{wVOINCV^;tm-iLb-})q!SG#;*rAder7M@3qxeiH53bO&=G*O}`uaA_L8Vi|gPq9fO zCHeIG>^X<*y6U(^Ly*oAb`}txZ^W{_JYrbybKa+I0y=a8ieMZDJBWI2_7YDO@vl199PyxA z!iVjEb0z-{&XuH@HqOqi25KOdWQ?90-12<4%t=>Y%=6`K^nPwTl?w#x znkt=mI~-slcw3IA@4ZYpkmo78AXMkJ$q;|uH17b{+&@{Y6+*;q(!6s7 zcyNL0ZIDhh$({7!75;(>?ZPDAfy>=CL@TeGke_>8KB zgTVjq1MYbHN)Jl#%A6q#YlLk4JDr&q*eVuB&e?LOmTnkM?6Et4*FFMsV!wTbO3@`x zg+YVuxY&-qfE?KO##(anSoIy1x}04wwlA32q;Vb)Y7>1p{O#3Qu8%?xI}r`in_0<9(;JB z2RPYaR2GuFkqXKKsGfAWq^25#6lnQJcTJy`e2-HM&nMZ^RUMY0AfuzQwR{xMG{VnM zg}yFbLe^Za;11#YZH9Fa!h#gBwU`D`1i1J+FZ0Mcj@(gV?$oX$Px3KEN|WND5H6hn zQU17ZUuu6IDL~b}JWb$jeyuVDzmMpZXNmnZ}8oz4@70}5(IM)6(U&szM#7+ z6Nx{4Dcqq-gn4F!aJWBqi~l7o>N_AdOEiXnUu`Rmal?mreo&hq_rD;Jb5A6)V5|m$ zwtPOQGK78jw6DpCXS7B=G$de{LENJXP+n zRj5J3^x5_Ci{!p$fyxzwMbW-p8&Tf>f$snP&0xXs4MNxZ-)nV&2_(nXFc`fRL$eD+ zU}fPWZ%9k@);P{q6_L!mUhj^RJ5vGagH+-^>M`hKh~o0S(81>sb)Q^l7c1P?pX|!N z^5ByKO%Y{Q8?jl}XwBnRo0PucUZ9^y-(J`%|&~r)g zuLePqE#6^N3oxO6uPO=22H)n4pY`Kz9D>(9s{s|x1FF6Ra@Zd_(OTh9wcKW%Lha3@ zPT>WyuMr%gj}08PN(=;y)^YdEZP=W#?v!*D9YW94o@y+C75!WE>wLkK^r}w+i(w&4jw449x~EHSH_A^KT1^$e4{p3*F9Zw&Lj=z z1bkvjNND@@c9$R`0OE&~63JmttPb$lGlQI*lp!h6{DY&{OBFwk`dXc2cBikrowxuF z8y&}GDcreyEGF@U{p&!=6kcD*8{|__f8M+Vp!~C^Ts(e}Vm}`}5s3Mtnmr}nOU+I{ z8p`BueHM4bj2&K&7euj8=h6tcMpodZ6za^Ge6_ULAOb2woa!m$*j|-GVduY5u@`^$ z;rX+La4X4D?(6D}6YjqR=)ssH!Hq)I)I2!Hn({!Z{R}37-@)QbuA0bzulOab!EDBj zbx!CxUc-^f=}7VyS6AO^+FsDxp%wf~fAtrLTn2apzNEj}b2i@Pk2UTo6Ot}A`i_J% zn9sbBaabBbTwU@wTl}VMxE78LV5sY!cm*_$Jq8WRt9zRzSTJD20!>qt+ksM2;w9Vs zVUot$*SjBz;p>%lt^$*iVy^b-97nm`M8N3@O z-6#dc^oarok(w8)9*vNUU^al3~Nz8Tt@s|618|^5ZM}L31*eelgwZHWqt2PC% zq?{_I*qjg!Vb8DcSP`hwEj27K$*)5OvL;K5wh&Z1!(}kDdpDi#iWs1*tQ^bdhb!1!3jXfr?dgkA=~i zKeY=+JXoUAX)l+&yLMM&>ntDEL+$EJGn%HAN^cJUmNnWFpJ_zvIwnu_o%y`@&O0L0 zV{37tZ(1)8#aLS#4gSR~9BxAZ-IF*EaX+4BF*i$l#@c1FAiU#81#@wmWk4|X;6^jb z;opOVqFM=Yr)|vKzKgln6K$zw@n^cZ!siGs^3DGJ^>z383!YBNTX;&x?EE_k{`Q7up0M*_3!zL~Dqwa8sopv8^jE~OsrB6&i=^e)of-@~HmnqbcC^2_Tl z{Hyj$-(`6F>d*}PzUcn>R!V+`x&Hn3-4~n@_ut0pLn`|>e}3==wL|pHB27dZpY#Hp zg8<$*_C=$6bE-feBler8S*13omUiQ4UOXUs>mX<&#YUZhK9blh_hK2-*S1Ba*8+zk zU(~s_`P>*mU37-9#!g59-orpfKLNcj3R3Yq*9P`yq9wz4^B z9#{@d;Rv0S0dmA4ptEhi3speOz0~DX6p9Nhy*$4M<|syK`T(n?G+8i|W2w@*JC?pQ zQJCXg#Jm&7_x8Hp2|3H&Vt1z6lbTb$G=Wx z0ph(W;=(CE23F_-q>oCfo3=2yNmd?Hy@% z&g}b#^NfYh3SELrU&UPM7kHR9Nv;3km^xhUyy?vpOCK*YeuC!Zm=%|>qu(fj6qy1= zaqq&5&AxCWKPcCw?Yf!%3eOlXR@WSQ{fiv3hG6&g$^=QAjOevS

aRdg#lKWG;WA90$B~>C^+rhU;`kJAAdwlCWj;mwS?!j__2liZuI}dD zs4m{#~m zkP0%4z!)x~nuYLr7DC5@t_eC>JnE2fW@^o|9rH|0-J&C)(V-{Ykb9#o4A?M8FcvX; z-DGDP$o}1PKU#V8;UwoCe#ttI72t_O2j3~1bfg(Z=+K>F#Vq;QB!_I^znYP$6u}ae z&SqQzl`BNB1F}-u*id(dkdVBGkYr#(vt2O<+rtdc{Vr4oxS0Ri`*|h;YFWx_pe=a} z-1CN;PBy~9{5*yaKcU8CVfF!%NWd@j7vEsiI*J}L5w!6ubtzQ(^?Jac9ewIbt-m`r zX@e23jK@^TAj!88$dc@ske4CIt%F5&a2k{80!U>igt^FdEMm~Zc}&_)my4Kz+U};Y z+>i5Y&_OG>t$NX!!dw{@nG7yfnP)w)GlHdCCkRn>lAG&VceHa&t)E> zn)QKA`{3{VHy2kgSWgT=5%qW#f3BG+{jg&jT%*L02NmL;9TTCI6-)egVPpgtH`%_>db8#N>8I$Co4`r?j1XJ)FL5 zlc7%y#YJvvQqFRXCkjdLzP{3}?>y97!?7iXe+>NkT$A}}VS)L%(Xw|Sa1E3wQH+;7 zdu5jcHZa&Dboi$cWgEsYEJ9}>)~;%A8m2u6W`U%BMV5!Xd7X^}1FGk-^{8zme7aRE zsT{#P(~fY1xtQhm5acW_)KgaF3toG};Tr<=U~{BkIzqThQz#m)n-QL9@sh|=o${Hi zA6YAoC#&8Nwlqqx%#FYn|9;Vvna?S(B1&Ve`_{EFEl^PEgl9n6+!O{E}-;}9r6}@LJ;&l0AKw9n4ZmP~I zLYq&X3dHL(k^U)G4?Z0F_^cGQbczRpJlYdG_$L7fjLh?+WDI`h9LqpLyW4x;GkW3> zWb@pJvNOH+j}!6nGM+Asci2IG>^*5fP=3FK#O?H-?Ra;;i(Dyf6@e2TPTQU( zw>OSGx&MXmhQ0v@v)b*N(KAqHs)@T6e~IFdi0sf$k^E?Ng(KGxs6b^W*02z*N=cHv9nPUy+(>$rOn>O213@by!E9yN%1b zcm{sn-D00#Fe8Zb=$j=s5E8L3#r%r9kylWke#WV{w?Fk9gK?}c4T8?2sfaQ9v$lz6 z7#F%y{(5%s)M`V47yeOo6iPlu0+a8EoR;e-or|RL z(^mZ``T9bnZ4APv^*SAkvHbgd8jY-x`tKp9J&9`#LT-R-GUPO`#ue~-vYP0nRoP7A z?JW*tNyY}r zXPb)XRAnmdpG0EUMh%`cfE#JCp-N-Lo9Cu2O>;|ZyIO)D7U$TgfDvNCC|5z0`}vb5 zuJ9Ot3wfldoxx!WyT*xkAMXaG^v$kV`NyV(Ox$Vu*`(!eCb{M`JH&775OMx94l;oT zFN!kkXUF(NDBqhe?_5X!m~MnTSqB}(Zw*Y;c48}MISHwFx=l`9!a`!AEHOCme_DRb zL;n!OJ38!*Qg%BYtPX@a@eoGv4{#8tB%a4#Bk4yJGT55~p1~!=Ncv+p0_%S5lln}L z{kf|`=R?mRMf-3`ol);D2KJU(>uWnvDxJTr_7r{&$}_9nc_YDi@oj+H2nE-A?YRU3 z241#8;AuAylTa2$IapEZmi)_jWx!X9pbMnb^$x)3N$O};qW@^SM~0pzUc?Q@WQ#UDNKIm$8Es6Qh)W4ZcznuJ@R+qExUJ_4%m~Yb9>TLDW z*6rMsz)g=Cp=_WWW8$a4TfdXRo#e;==5L)?PMED)fYD0|7T)890u z4L8P5+ssT-90}ZRj=khjODJe|aoFqh$@el_`zJ(_ z?9=>=_8L-p3F59P#E_x-)KF{L14BsBKsfIv@N0iyVUHzUWI~K}{PbbI zId(YlcGWAGX6>uGG()i=U#;%Ci$|A@0)5+Lv_@|o=OalnMuj$1PnJ08lHAmr0Qw(3 zXP+1bP4}MFvTfRotj7>Ql@zdDDgB8-AcB}vl`+>4GDp=%l)W}3`@Un+d;e!jAeR8W zp$JAOj0dD`C~IwwT5v{|n+igdFYB-?j0_jsMNsrHGMRVARlDRmV0Ab;hMMQfRGAqT z8uEk&DQY_rY%$M%oj$F*%3bc2!Gpx6Z2{Es70@O6t{{G9yacV9`;w6Q`OH-7v)oi* zp9elO^`Td-#&eXzB5}m%VB@_7-noKHI6ns;w?}{&SA+;Y6@&z$O=p3RAZ` zk199zqmf+xmPmG(=@=?z)UmM3p{7_(pc+B&yj6f=zmbw+v{8aK@NBKy<`-!}XTIKC zgp?Bp5h3R+j?qBA-O8voqX_?<+6MWH-wI75t8t}pbio&tb!S3HLUMH!J%LwydjbCh zgG$Dfn~`m{-fu&H-BM`EyvaIb)U1wo5TSRxPVu6p7BC6i<_$LgEWQQ$m{Ij}eS(in%d7xfJmd z9<(?qp-;PB+J(8#8Uam5e&fpIG~Z&}VLB6MkKZcyywbj%$=k3A<9GQt3Z>0`gEXS$ z+BQjq$lW;oPJ3ig*o*h6=+ef6^wVanMl}DN(mbc{t-5lBd%St^^P9@U4ta5JdD%;w z1OY<&>Eg)daDh=!*~sS!>LLp+{HZVH7bFi&ZXyddTvca_QiN`JNS%K#+r;&rGjmTX zT+!D;m^W{!HwPDWH^;@sq(O^Te8Q*5wh5fm8+$+1k&)nsoI4V^=$4*9j*{{nzhV7M z&6h(WcJ&ZcJUPEDGZuZ^!{|$Xora~OzI7p(2p;fxMJA93vB+5J+?4dPc=b(qSqj5F za+qAZ=xX-oIWsNp<$^N8Wl|4gPdA#)1I)OP#SujSLSBM3?ct4){-sGoNmyyzPNOEO z$e5l|zvWzN6CS*83<T4Y@@ILrIo zF{EW4`9Mac=kt5o?M7D`)dgu5eLHR}GKB7ZhOj)naM_F0KuuuzFg`JnK8Uope5QrU zxj6j%0NI2Q(1cJ$$Om*I#=8duK#O;gC)Hhj^-{`jpl26MPU~}@&CWaCs>*lw~Sya)GF7v4RNMbgG7D9rU5cb5!rRaxH1gFQ*jTCji zIHN>z+wXMQRir5FDDMa$Vf3aytxhP)p-e)m+XGq^(Ixpcz8)f z`1{r#h%?rJ@GdgWeXOFC9bvsg&Z)Dc00pbs+g{l_Q+8X)#5{@A7|VG$2liqaXB< z(NwC{lL_yx zS}<1A0v1PqHC>e1KwSr6gnvPy*}WNb-}R6p8N}6P5=|Dp@eoNeC7G~RcN4t`!j@Y8 z;3B>I^gd)9hfmoLcdy5POU-N~%j=%eVK2V-9I*JgNrA04udT) zh#|0r({(w%2U^qCK@yUcAnnC=5$JL=2Mf=7CBGjw&6>} z;6|xSK>tieNQ7D*h4n*|<3U`@%1DJ8Or_H2FhFDMv6^00pcP*1AmVbn#yAL5~c!<(SyNAaP3dA;o27jaqm^|z+sR++_p&%EfbW#xAF#di}e zECfMNOgw!jaUS*{m)q_$cXoa{3cdz`RnZsLWWJZ&>sZf8<~-2i7S>w3T|lIfl(08P zyo}Ma{Cx!@sn;9(%x1%AC2na}DK2NIuWO(cwKdVIn>E1(-KXMLn3QC$6XG6wn?Dl- zpZ9V0)pk%`=<5&6OrQ9QpuE11N%QlFbnc1MJ*h%!k_#ed<_!^CGW|gue;X_;lGQS# zAyqIX)QRmm)wCSWUl|z8)9xjrvW*}VsgwJxPK0Qhr1OoF5pD248~OsfgTal|C@-4; zQC}R_qOUnAJ)zV03SQ?Tr#OAdu=v5dhsJx&9q*ne_OV)f#)hOvVy)+|aSU+Q;$GA} zqigh-qncKNi#ariNJ1j|J#Ej#OFtx$Jj$LSi)ser(~n9tr)Ra`tydl2OIV0?#+GQ* z{0jleb( ziKVzVRb)QiRq581Lz(pY zHDWJBCCDB=1_I*ZNG>8z_jIm0fmx1c=E5pAqE27N zU3?fguV|0ngKh+?j4_saO4XH4AN@F9)`0PM+7+tkRRq2nPBibIFNqD-K8Hg3tl-QK zI))FJ_iy+f=noL;aS3SU+^W?rvY50IAI#So?Bl;3D)aJnJrzOeozxIa^}_r{{Dstz zzNjIf;8JLDd3M}ypdU1;m{v$_zJ8#| zScqpR5yERo+$zpj+I>8DXRO=hW@X892Pf4*0N3%~UaE%}N4+ z!>rfxs7W{=JI+*tI0eCbjS`C|1<^;Vd*9eQ;MC??GyMXJwia>COCE_q$x!~}G0`># zDz3S)BzvYSdC+~0^3oM`>kCqo*d)Xf-tU(YW|l9LkQU$*de`h4eF>k_NilAB!nm)o zv}EqnQMPJsLTKtJPRi6-PW9K{Dsi2vr;o&NFW&M!D_wfWgk|1RBIVfhcFCmd7|~B~ zxS0oybmigXN}ki!$7qC|ad(HF>`k_%7Li!`-@Rpim~?5s!o_(ejweS=@`j;22h_{G zs^tLzY2vCPN#F6?zQrnr7K|PBH!Pr#o(>^>PsS;ezPvh>>qQcudhOQp!3!AE{a|7E zO+9*zN$E%_DtP|NaH{WVKoXO%iDXeNJ^(t&NHe}J#4OYF5oz5BZrAOnYNt*`I-)$P z@O3-32pHsd3vLpILa0LdtUR)={ItnfnbBveSQ2dvAOT_Z6{}+qKq-h{YFVpnfWR5_ zPtHYTg3Ddd5AT5qvhH%5e2|D;Q>6|l=*mZEgwq^%fQhd$YX73f`r&#taejX`m8npC zWlu}JtPdW?+9wEq#RA!3mWqA%=ptK(*)7U54o?ccXbISwxa!%xuOGucrdxINtGR#* z$&^o$ANWjbQ5I)nV1e0Dpx?ZC`{xBu|J`qwfpze=(SE@LgwJUl;f?~%3zsO+s!dVF z^VQTaOb^s!JJI?LJ5-%(ner$axOgSR_J(+iE{jzK>V}r z#QMnSZGtQQ1thjTyNrN1H$r|Go^%OZ-W!?dg6h+1?u|UsozAL8=APLOvKvS`Bu5^C z;HmJ*Dj0q%DY4_gye+FZCcnP={p@f4X9TyUE)3(tAIedz$1*+eYZ-Z*HTz(IzZ zdiY~V{h8`nr|4A=Z(b=kZsV7LCHCW&QUPaDnT)|D=&}d|RVgV#Q7c&MVyxi;m%n z_g}=Mln6s3L(NNcUHi%ydb}5KRCN2@He9}BUdUOPutvH4EK8%NL=dnDq*LJ4@2$B# zqq7rja6sIKUSCLL`6y=@qtj{>3$vp!MZ;I|Gi&o~sTGfHDOIT=+RIaRDv&ZQ?kZK@3wlw~n!1S=4B53<^*q<t1B*YY^I`aIWm{l; z+TGv3&d*SUPlE6G)7WmKZd;uj`v=lqv%A0D{o-BuQ4GTDg1W>C0WT>tat3UR=Ui_% z>BTjTC8S{Zl@TV2phS>{dIb<)IVKME&6aJCVIwynCSg{|e(9||tHO_RPPJ8s;RVk* ztdzR?81v)7K_W`bT0{VG<4~Dx79I6WjoaP_%QHXeV74oHtF&wk>vmW7nMVmb z2qjifxg3Ek+t&;hsJCH58DOyn*?F?5fN*_ktKo}7CV{CT_?TnzJ$pTcE3Sc2ZEAQX zhuZ7nJo{?M(bd@PRv+72lLKp?n|AdEDKBAzIrobR;&8W~eXu%UU-ypf;(j<`)APe9 z^D*!PTy|Cc%z0b;s5PT1uK*w@QTmz`IPbM{ z#+IPkb34DV@?Jj8%W(HwGF{st8Mf`^=$u9sALYUJHdp)|JtP2k#DzMMBpaor(ja^} zh7_4A-(5}~S{7V}_#4V0Ls_}n2_xiF)U`>D7h|r{3kjaikiw{BMEo>{5M>>B1iT-Cy^wkt;ef|n%>XIzU(Dp-p)q_VuI92o3E$$s=-&ItK zxu;C&ca|EyT`8>p#*s+|N(;*{7zgCa`-?@_P5WYILr{o=Jl#i^eujUfoy?lKj1PgM~pjMWvcT2ea;*C51W@*1z$)y^Yp zp%meL=zORpTx}n2PVnqOkrvnBS5)fAw7~!7?{U*=Z_9dMt^;o9Nq>O@;l_|Z(t%zNo?IGA8;~F zj=%4R)bvx*I);SmpWn`nf^dn<_PbH#Dwx{DX3;M?U<@viYVw?WZlClrZ%$Swt79Qq z8dO8FCDk^N>hk_}%%UMtnu=HiX4lOgvc7pEr#fNxojXlO+@&yP^UVX3s@7%lULH0M z9w&x*9uWW6w9NM5ifyN-2ylL?jy*JG5M$ozWyZSvMKYp(kYct=>GRGU*j+D z>zi*?(TshlU8f8$I?aiDmZp0vww`;yUu^KspMKas!?zXKPUsDT4i*gw0zaK0Z_kC# zxkLC&^vlj-fqMh%bD66IC!4EL!E_%rQnjX~t-&8D;E%3vjrayu?V8Tp>GF>8L( z?v9>7b$@;j=$@ZcXVzR?UBPSjdtm9$8SxMsfbHzjbdt*Ly+?G?s`&Ssy7*6VHJ8T+fFjK)3YG5(!3qzVPkdKqoCDeHojUY_AgUpZJ=;2BbEa zx9O<@&H2!d9yP1jHGB8H=GnTgsd7b{%C$%LsRrMs zU@s@@2$__*s|4GtbLxpzz36w6aC4ft%?vDs??Pp~9h7DY<%Msr_P3ws8_iMmzaY)! z4l7AeZXo?C3T!$_1V7yS;^$oV-0REZALssMfP@FjMotk+UThl{NoJ^oS4Kc$q|j1D zL6e}wQbqd)>Mm2X-1(R+ocE8G&Oc&w!Q>SDX!~Z$NutuWk;lT;{Yd63nJ_}K`ukAf z$H5=Vx%Cn<4*9RxF95a;o#I)aILdavdAp)e4L}2_wC(qa42u;0Mz{JaQ410;_m@}Bmm9md2lPH#UEF7q3bKfM3?Y) zmJ-FMF*C6{3pe>kA$ra;?3LZVoe|mi4T1Nrz{diE=j++X>meC42Onj9x?aeM%Vbhc__qra-d?}Yo zHL@bB*ethulcb8w31Xesp=}KZC*y@XGg07VX$6}_hQ{8L^#RWl#;L%WSa)-yHn5#t zwrDfxc_XQf9m<$EgSPU=Koa=3BtJC7<=F-hh9W!rj1bMnS)!7~@Vql*2{~~%YGX5F zE@DP49_^5UgOsL3H6sEiDyn-%Wi+mDYq?tjFp3ghOS3W9%3n$;B+_8-=@o6wfymoK z?pnXG2hirDH{Pzw>96RroJZR59aC4bqW@)iML)yPSkQ4K3(Lcfj&~$P;1y7B1`|&) z+QegFhMbiG5G17ikiqm{A2l0?EVH1|Lqq!eW__4n0&d`Z+B6$eudZ^JKWh=kIQrPs zVCU^z`F5LE(Z{J=z7w{pZ+u_ynuDmNA=O=gk4H@r+$#g~)CFF#zG7=aEX%V}c)EVn zgF~s0EG~R4$~atQz*D(@3+ozHZ@$mvdl51i(;v-oGbE3$T_gtkDTs(CWpl?<>>RtYJpVhsKUP}_i^WyNGJN0cix>f zC$RWMoE;7Hi1c@ejDn&xp3Av}iZ7&9K-bV<#i2Ym*Q|Ry~tLVd#J;DGdRK>b>J?dIEvqcT%;I|Te?m0`5MnC5XErhLQ7d|9%BNx?$ANKxu zMqtOsqV^8y{TXaxyb;{y^7LwQUqkd0QR-gbT|%ua>3M74X4dz|($n7Pw3SN5LHHja z`*?O1KHm7ni}OZ45Ur~r4!cLw^KikqyAhf{6&6&G z9)VK4$Lj>sVTvoeAdV$aqBMURqf(<;$rzRr`s`@wg`uk3HCjie zh7I?bT)xJ31WA6OsA969FImgP)v#dKX%8)ye;L-%XhASf2ubPfAG{b1FPqr+e=}6u zb?rk9Md{-~p;nk}XNE0K4WB&;of}ia$DVx2K_G%rtHQ1=v7o?72Xvj8kAP#D??O=a zB|`l5AtQ$q!Dy9D!meR!HnS-Sb{vdnBa$qr=fqGsMjspz7A-)JV$k z*}eb<-?y;7cKvg1IteCaEv}gfCmogU%clO42M?IlDv`x3P5Lrw4VTigt1!qU$aGgX zny@EOD&dGX>Tlm~uJmZp+u~B9%E><`-<=Lw$v=2PLlRT(Y->VoB=P#?O}@AHTnEd! zvK-l?!S!{m*3EI}IlxTwKWSm+@5^Jn#`qj=yv0Jw$|4YY1k`B%s$WOxSX?3wmrrj z4Z%A|mGQO2NEHw1#j&WVhwzSdxOA(;HD2o8%O+m*%q^e=LBNphBG~WHV zTeXPM?l=Zl3M(v!riFbTZO#7kU~uD|-vr(;{*8d1cX3?u=)H=$^J>wkCR<7?1VPe9 zt3?p6TyL&DtfF-<7+7E+v|N9`yuOjXdcGZGrQcCze}|b+9t3CC9ew;}|2hh@?8vU5 zxqi>44Nx@pRTSLUeG1?4g61<Hz%*DN3r#W;gy5m> zUT6zS^jcr<o$@dCY%+|u3Oz!L8FBbi2)XAiyNMAKxFKA( z{WjTc>3d6Y`cNIT^eS0C3v~S@RVo}h9nlef+n*7k$-(9gU9+J#8<8QHIJ<~f^AFh= zvx+%xgpwBu35H>0BFy+#f|aT=6dL9ed#!;1|4VNE%Jd=%-Wap9e!%?Tfh8Oy5%GWT=%18zD1D3n=J%i@T1RWDJPrG*OZ<7hQvO~G(Ts}yI86HRbJ@54z zp3xE$GoUliGqL(tGS0A6tFh>ycaSmzX064BTF??2ru^}V z>?6I}4q%-54=v9~8^cP$?Q!5zyt?Blyh~1|3cev9H2C*}@m5UGfts&?BAOKO2i5qm zJ7kKdR{p|hL)_E-R=$!j4fqJRk#Dgj~F4K|s2~(7`ACEU4 z-9HL^$O!Y>O}2M+KAt1ZTz>me49WH(N2a@w6qwq6@wunKnN}9eMW-e=qanY*{E|Ic zSPTDr2M74*@jbRGHEK?dD>{;dG~1{nZ&$9kyG)5hxf}Glt#yS*gL--4pG}%WyD75u zXQC{)L5&3{l=Qtr#yxwN$A0LegC&zt6`A!}rC1}HI7v=^9?R|>ri<4_jvX~k9=$Uk zONL6yj91 zepV?s-|C3myuT>@V7ubC3h--ESa&6F!_IoguD{KinfqJt3t5DRrHo#*`eHoa)mkl>0;OfF#xuKz4wnh5wsTwV8lFLqG|=MW7-mof=pSoa{!@^KxaX; z4nR`)g2+C~TRSi=mfg8Y2qB&Q`QBTxrD>;-k$P3bavuew`@u*OYvpq*8{;}>yp?)- zC9tYB5(abM)xus5q!$iWe;fAR?tpJz0jN0PO+_qn1(;?1`nYyC7=D(9rebfx8KteS z9<|ZhIFjccM!l-U>e)?sEL5fc!hG?|-fQIwZB{ z5{6E(dDRVreOkQ$(|HmL>vqQk=7+abU8zqC4)If1jDnwu_6H?O8;rlqQ?9UKexpeJTAR9$CG4VDrIA~2l~Q7N7dvg^mL_#D|`%sP3m z-1g_P>hhD+&LBQIt~_ovMX=>9wM_3RZI3gH7v|8yBf;{oSD~s3;>x3lPfZ4;*$%OR zd8Abb#bUnwAmCjhN~BPHw&e5TpuzT*76f@5EgtF!mb}XmhC`mEZG9`35ghdADC%2a7MvvgE)*x-p6e~chf7oD5}7S_D0adG>~J)cXQ z2m!>|PHY{%&b5v7-aL1bp)zN;$aZy_J{obJIY@u`m9+YNyhWxV-y;4Tx7ItGq?TCU zi08Ca6fW(!e1-Iz_ah8lu0sTe&MCyk&tGA`>=vb$#KbXCXOW+zv%=6FLUJT z*Em$V0~Vj=_FUQTe84-|6ba0yyc zy)n))3VjJ}h{lHZEO~8@nI;O?NG4ek6AKIAMjod<$bI|Z-^{eP>|Tmt3{8#3*YxzJ znSroA_^d9vI-;i$Xk@q~>Y$u;F5Q zm~aH-jLamaA#!cA`a=}Wh@RvfodGBdSQr0>l>h5{hxZ^XG0rrQkCj_ceb+QsYRbLT zX~tTpq{d^YPQ)C?7fZ&jr9MBH&jAV9*y|79$}DRMpdJ@}&~RIM>_|$RhlghPg&DpcWr{ZrVz-KM+`ExCw>T)&r<0_R)7T{IZlv;b=j$Aj=I&#_ZhD_wzjoc| zUpW~x8Qu(+`8U;2DGn&SL0|=kJ?S#RbtDS@4lY=_(_P8*hu5>Rzy3}^`AeDtg;keT zYAF8!w{P5)B9>NIeKG~D<@%Jg|0EoK+6(2~c6Pt2VSy5-%lawc$?*VTjx6jOh!7Ch zXiaQalOtP?1-qU4vUqPeT7dhVl>HB>QMZpHCGG?gf9+G^=JwdfWfQowfm^EoWW)dU zErMYvp}6-KrRxjC|5g^uA8sEPeMET_eL%mCIg|KNiIt@nu0bF$8tjbzlnuh}w{Awm z$8@u(0xxAac9FDY(o*iP=?{2oA{1>lViyP@RJi+Kpmqk74AvG_Xei<+dq zO+tYiwCZw4=IY`6zTT3uF)tnYFROF-Hqa=)k&+X05s3%zn2Y13=gm%ykd}YdAKw{` zfn*c)$;w;0p{&_Q9g{vTt}-9$i%EXY+O-_xcL>MPmp~z)KheZ_Q9?7z+HS>VJVC ztsz9p#xJ^~F-!I0Ci>I}dB4Ipljz+d!Fmx7tK6(jwQ{^GD{XIUA@@3wsc8P-wxzYjZ$?3?uJs;(jcvLgT26I@qp|WMJN^e(r(o)1!~5*D7VNI+I$D_c*mQiJ z-0pf5Yc{dNOrI(?6RY>$;krkehn>&z1_bRaKGNgKp2QHt=#rfz~Cy!3!D%@j(8 zWvwOKgLZO3Q+hH{Q#wOxZ@j14lx=Ue#l_i9FV;HmxSVi+$fhP!?JpMcpSv@dNp#0c zFgRDLHj2?Bmg&$H`ugS)HkA}aEt;ZxfiL@``O~)dbjn3fxmuspwv6_3hb-0SdwJFH zi5SnUoAzWIVWVO4D23?nPAlutKdXk@)c7#%6CdF8O>Ta^45Pc=WKU;1DU1c`iMV8K zSm0*~J1An#H7zXfO}Vchwt2V{DpG&BTTs~d4oh)-f|T9FP(8(ei(1K z{I5T4oZ7>MWGfSu%hIYV#B>1Ba3I90)lIAvaL;%)`pOK}-i(2D*tF_&C^-qBLsw7Q zCq5>0+Cx%V0b@fhQp`;CTI%Z-u$81;N3cp5-pIVm1R^Ryii@ zogC+1cD)mhc@D^sHz02pE`Kwry$gr9OegHun(h^kTi2NluDwd;FU^_U-Uuh!&g~O( zyG>__ACJKn7k3eV;+TIs86t+2JDr;A1=h5XmoA`f&y<0bl_BUB>m#oxa5!Jbz7Q{` zLPUN$r>jVLKMEpwk8WDTX`RucuTOp~@T2_kU;O32izRWpOW6ap4AD7HTE%(_9$D;- z4~x39-bU65f1X!~fm~p_Rh@Zrt;}44P-fU=_Y)x@Tm%kD3U_%^$0N2M9MIB#7b<#K z(wxA7c7|QrvoWJR3!4j00K3~~ZO1N-GHUD~p<1fb573HD`e=JfsI*mKxNOgTVoF10LnGegJ^jqhd1<_6k8>ojq@8TDX8 zP?<-EeaK)jNFS6lIZ)27L&HaCtF8L0QO_y3OmOtf)<*;wsE0HJASXMg(^GyN1NFIT zm@h)i*>-k3QfCCOuTw|p+f8M4>oE$cc?#vyOv06mOlS6j9LxLA6QU^Q1hp;H#17CLZ)uS!gW<`^2YBY6sa_}Z- z8>MPE)ZGzRE5ZgkR9H0SD-z43J#POm4{8mgGU@tTi{s}bO{<=LEu~iaQz=WwHgVP^ z7VkU;n(GgSmbiAB8Gpr$l|ZJFru{-TMDGBir+*c3k9}n@`g?AZ>3_f=zt6=G1U+6J z&NixwPqnYX+q@4O-~9%PoF3?mh9-{f?*HY9{Pw>U5OS(V(`skjuMH`#P;ab~u8{iR zF{&<5s25t?T{IjPsx#2Y9x}EC({`!SRpAd(SBsMAUiH|Uiruo9C%Xaknmt%S+pr7U zpb0&;9{jt2vXLu*++H`j9=9=Ue`o&ksTQYbb(wviji#UnRgm^$;X*0ZP8w$D$07g| z)YhR?Ww??MKa9=xp>a3q5Ka{f#*q^JUQUmL8Y{V>4~7|5W7T?Yo7rm#>DQ?LRo>>- z){4Xf=aUlZ*2n0;56c_>?arwOQ~s`88zrGH79b~ixB69ePo@$fdN4NSV0XCHMRc!y zQcnmaky@!-D5GcEmmOYcKB)LsHTTlqp)L9dnf#tK6$5LI)QIvUF^`8b00q+X=0Vmo zC{xYX*4HCICc^z??FfG$(r&It78I)t*mubeR!SXA%)^X0uAg=#RuuGa9==hDD-ute zPo__b0E*$==o^xg(DC4Ot6NDo(_+blT0Uj~rlfg!O#jVH677Y7@@l7ydn}+lp^2hx z=XKmJj=61w+;-iTS9~qV1oq_Ur@|Me`nDTmngiY`Kr!xFQ|Y#ML+cLgnE-R67&7(g z@2JWDsm2UTRu!DU#$!MF9HOs9J@E!g_#9u%e+2VvkRFLIR4r)Z;#w zE(J!g+uQg?LPu^|QrcZ}2l&Ya?o8SVeKwOVBzs3YV?H|eo^xGyPWlEP!aAM8<+-0_ zv(i80kpi%ldiBxm|FBB`G5SCJW>td?q*RdIf|QW)!XHX@XId^LYX!znd?}d7x1tN5 z>h-@{HV#|YrwMv$Y`FyrEW!ualz7!A3me zJ)u|GicavB`2+g-X8}86L!}FoYlf}2F{k;+UxX&&II+jykN{8s^PY`yq-E}W`_GUK z9{Z<2KaAkJ#}2EC6jyU*`s)|0KwtyBo+*G6McZv9(b&je*g)ieRtgw6Yet&2dAt^ z$RuVskI3~DDoVb&pIQk7vD>@-8)g@yp8~!x;^spei)r0{QPwm|sC7^>F(6j{N7RBw zG?Fhi|6TGO)w6ktq!z|9iONQy^ZI-Hd?B+PN8I1E4^COW;s7gXkTscloLC zc%r~>eKt&17pTM)h%a4;YiSU7E#%7E0rsdNLN4DS8v~SaGIIK?h97ne4{JN|c_|ML=S59>OZ`wX`_(@`DVNFX4N5HR zWX%}N6{bdfccN*s=2+I85?qEgZy6~y$&;&F6ju3t%BcpTvI)CFvW8Fn6JkISYyBTZ z48aMZ_n4hg_q(ucfQej=EcnBjna|8tHCtCeyW#$?b~F9?~g6`o;#+EK{R#q&9WvAT6HGp55`~Y4Spz`xmv2+gI<$V6W*2Fd`}1^ zZ62bcOF-&G7Jr`Yr6%xSIYP`-UtYCLv7Y;3_QteUIt0J5A8JWEFOr^Demj;|X%qTY zu~IznLN$K4IOZp?!+h#N`qpOb;7Opycfo>3O@yVQ*73bl6z|nHBcFYV_FAhjN>A#Hx zxN1Ay*h|&2wJ{hlmOWf;28xnRpPCD9PIToj#zGxrE+h~2R)%(@20D^C;T#+xhP~d} z;7{bEBa}~pe+V!vMu5CVXPtNS=hrcCpCU$^ykPwKZ=o@eyn_*_v*C~#mHbwX^AdWA z&u~SlB9%q_%ZSprfWNUs)%=_~(yG^FW1;$vMOe60spT@|8_l9ZF+;GZOm22&P!-kf zW?($-8ks<61Wm_Ejqbl4ew{)^%i`&K6UEa{loo* ze0$LXPjstMH_uREc%Ru#g3A$ z1){wshPQ{~K8@RZxHO;Jo0y18Z0WJ?k|A-m=DvTv_VA+0XLjIzUtJ}`&mxEyo+J!?kQ6(;xf8C!#aDby}*G&)^j77eBG^O!lpHu4FSX}l)&XD42 zuuXp{Oa}jIOESf`ZaaB?_k^e$p2vqj)b2<&hW_)fki}y+dtdv}$UK_)x6}ZumFzx8 zN41{2+vN}fKG=}*o2LaIr7lDdCB$Z?|H|t{mWa@&GOq%a`w`=vcy82}<%j5n1&s_} zG6&7*6GDT3QKCkWBJ}s61^!^TCIM%5EWzTi*x-esVuKG;#s4Mh{bo?OiqSNZT~vqp zLWb!hRn}Y!`Zs@H0`yno3(F`|=i>ga4p#rKPj3Ie_yS)~#eqw)1=5@*f&*HWPS%(N zuYaKXT!<|NPMIfVF4=(95|5J(T8Q6v)7*i@HaHHZ7XciXIj6p}`q+X^Czgj+XCzNn zp?y$L;oB0|(Jc@G&T3Y(Px$;#JoV&wvl4yUy16glDKwYYRJhi!+spQ@^^c7T8|`Ui znN}PfRgtbYe>@YD-@dDhNf6B-iA*(3$TUq*jDyPRwDKuR^nYZ|JvaUTKluOTB48u; zoQzNJO)XRGZ5>=(GnE-HIPl}jc4wP7TGDqGXN(e(=Sh&y()fG2LF#P14 z%AJos&bzGD0-#!2%5=si9h?Js~G$KTK;``d#*^#IW-Tqp-IeG)8tK0;lyZq|Jg5^2iO~^<-Non z+J-U~iuAOwx!CoNy|Gh44I(CCC_r{o1ZruX2=0JO7gGbayy|UXekh-2v zUs|7;Kfrb>eMIV~CJtzF+TBzCO!x7{7s!y4jn=PeV_r=TDJgM<6CHTPzptH$y#MUM zi_Z&FFgyQ)jTcc3!Nmd~s(>;IGP9uVm{q<1`4w*| z`a?)bNu@&1krO9GAlKQ(Vqh#H{`vGw8h1FSX6_M~ER413@H0~XUjwZ@7mZB`6>{F7 z{mmd@YCq*eP;G}u@L2A)IQhN)CM6}M;u6_oU?vcNsdBOAQeL073WSn$WDM87-(q0i>{5gHmA3`%<)`M(EW3o|pN-|_Q{eh6RU zyaC*^xc}@5%f;k%>XzszXG;f-V|CGD2}}|Np5}iHioM!>b(nP$eDc8emiYYXkS(JV zRiM|$ro~4`ucxzbvAKPK2Ps2e& zKOz&6r|yr6kR#WEe0ZCj3{tpAE9|L(fkr+Q1Yt7PccCsmKOW!YDv7G3Wz+a<~9idy$(Gn0$5 zR8Mt(!>zY|oNC}3wds%9pftL*GlUSG31>ewtlyDlS{Jc<8+i-bmkcS`@meg z#35+e0G98Y;_FVin)mAO_)ztq1&7BJ8pXf2M;0;M7Ilo9u5~JO82ey9Udqs)${i+T z)qQk3FYhS|d_<9kV~r5YRo&fAVwe?4;#J(>3{LDOkh|4ee`|3$5)8J!N z`ppK@X$nI@_tPeV%a^kfO$A$S>B-lujqDa5_;%w96=M@R*axfzqE#V>NVg$HmuvSF z)e3W_&Uxe$X)ec4dv`j_3uM&gQ6TgiQc=O9MFVfk^g^yzaN-Nh1~fbeojbwkQpvRv zb%SbaoU#Nd#%a2GTXZHv3nR8UNqQWcD!1$_?S3*{aWV1(eiCnvrc)G`cO#;%f!GSeuknMbfG#Jofg=OnwRxXv}L zJH2{Cm4;gs0T!>cTXVVgdgw+7D%*D&AX2DmCAKf+<{`r)qlbfrL2a5K3*~1kGK+V}VCYN+ zR@#wsnQZtz=K}^%k3h>2Z2)=t6~VlHeiOH|guQMAbjPoK$wsC>h2)Q&5kZ+X^cNQv z?!4hH%J&2XNA#anqNfw8dQ&+*Az^l!P(rK66W>lewgtb2-b)ooHYE!EZLcj@s~^&I zXkZCTOzeW%-CT%V7TH~np7P&@|FC6bcRpTUai08_+Xg(`MG(5Gs|ME`L4KOI2W@h- zO-KaZ(XBIS*#prhn4g-Bs~gun{dP{@O<7?*&5G}48#JT`qgd#zz9OqlPv1sYdiOXO z_LPRigz~$6Z~S6Y`AUm-!ex$T%9H*{&Ie}sMqOw62NscQBUX9-Q!0D!T?`*^8LB|R zjt`yVy|DP|-&XOpNX?YHu&5v^6N8CzXzSuT>(BcQ;tdPt7~PNi1|Rrm5@fHVtyX@c z41(I2G1P>Zl*E=DPx$NI{fPlx^6T`j9W7pd@n_9dHOHD5B^o%w`PA?W_I8Ls+twqT z!cvyYac=qC4#%ecwse?RHKKkJyb;4|+%mvmhdGaaYL+Mjo(rVNtkLSfaU5#&=BxpE zV%pC_nbUOTDTSW9acHsEIFmT1rsc1*4avX{P#@l^ZzU|J*dZN(V)x3z(C&bF;T=!C7Shw>1g# ze9rSNhK5q8P^oje%4K)larRyhHPYk;6t%s@OvSxia+fPkC##ha-#?GKlcTn=# z@LY8DX>W(j5$Xq%;o+pmgF}XagxdpPX=(jjf=TH@o>gkcn9E*)OJe8%$o71oKxbd^ zS#ctedh|E)rAS)t7bW-y_~!qZMmIj)4_c<4Ackz8?;5<>l7Mm(#iaz?Lvh7JV4PWur_wy;~m4*g4yvseF&>Umuruo>noRJ^$)jrWSc%c(e zk591kp*S#G7~m!T81h?g*}jmagCokV5Rod~;-Ocj!(t1*JE4^odYTY+jrS(^tGEx< z)%pf#`JDADZ0xL#jhD$$p`Or??8YU(r59vijn)28?w^KZP`02>3%4zhA7XTP1Xm^X zq7D4{kv+G$Q5jCC3W9sFDXN6@-?hkh5M{Ggo^OjC&JvI zL4zuV^PVV%>$~yTQVkeY_bxs?6BE4e7eJkIU-d3}sQT%tm|_3JHIQ$DhlWh;xjGy{ zD}UBAtQhV2qR6}s-CE4^yfcYh25ZLa)XB+g4fhBhEJ6p(1hg3#c5j^sd5!nC#Uf;^ zZlN;>_#R_nO`Oh%_9(#51KzhG>bh8N>QJ;*6a5V*(YJ-@dk#I=te#G**z004bxf^X z16N6zj-D$P-0!mnF-XC9@3zoAUZBBg6kYan%}=5siA-e*)o)M$I3Ph)Vc8g!^#Vsh!!Js4sWT1;-8gi`-Pr-0x%)VcXlE5X~}*O`L@`;ljJ z^ux2aGeI2vqKKT;{!;?w>)mPlQ8cr5d2AL`iL5*Ja4?SF`+jYmx67IpnLCaSEISFU?W3S12UI< z)7Y1x>^?E6<*!`BIA5ipSS0Yz`_G!bXngJI4E-L8WRj1jeew2aL7AM8Pv43UE8+Ge z_e~egJw4vIOqk-hSAm%f_mfO@i`<6+4?v#KFfxZxyX0#58;%d(p>j^*lhs1`msh?z zE4`NXUm~QLld5(e?(1OJAHote&J>_MIwz~bf)bp&2Mr)C z$j4_)wVa)A?t>Y6%!{4}1mGu?=$8%PyxOBHdtRUPT8ZD+?Zl^k8td~MPHDRuJ4LE` z7sX?ubJ*AZih;-XDtwPV$;#3SGlS0EgBBoT_WYGe1_@bvP?*% zv@8juulkN7%>h&P!WaRMVvX=&nh^;}M9rrM+Xka0y3N(qh`3KFmO~k$?%5OMlyUp0 zYBB{cgIv+5tsh+GbjJ0rX`6YWdgUh3<7LKQ{uVc=Wvl*>Ig{${^R`{D@Jq|91wG%D zxpbT?qj_WwX7slu!;r+W zs&!Hm9xv~z{IGwP{gAl-McKVayF+`D=lQQ}l^Mo2(RFn5g?}f&BZY^Qi=Dg^6BkH6h`{NNL_X#rvJs@>j+z57Jz`ekEk zB1Evu85oV|yH zuwB2e$W-B{5+R7!#j)bwJL-xQ($75y8DOZ6#R}+xlT{Gpwh_GN1&PWyvo}^Z@S}DX zW>gcB9Z<}h1UI>`tkgvE9qFwtp2dxyUs@nNZdxjzkcpEQZVO1)8T8^Dy$jj&E1nv^~x&a6i^nGoX{pD<-l^ca~DnVyL6XAwx@F6`0p*1=}dFj zowHR_+cv@Y23iF7b86ShaFRaTc1ioYwD(glMV>0C0wn@orDw9k2vfiFh$&W-RpE`i za+2s%+bzkUo;9~3>k2XFS#_0(qja2<9walfE|@fs3d)vp`J&iTPA*QB8PNO8tz%pV z6eg~thO|9M5Sng5h^hHkSrh9P!UzL9Z$2)1)6>}+LQ2{41pc6QaS2EFRLc|Ekz0E- zbmjsIc_F+$)p~qi5k?iV@@R8G%zjE?`1OxRb3u@G3((*DdKm|cLrGVR z(ed%G=DuucYR5+oPE0sUXYnnYW4O^+7xrkh2*DdBdp_}}px^VzLkj3sQ`EW5Q@OeA z5X9Ynq=EtyQ3J&sNlef<%&r^U8591FQ`NEP87-@JVK6%u&KuBq)few;emV!_2xYf_ zPP6^YREF|3YgTKXkr5ZWIl;{ZgN&ra1*b;q`QQlD*WiJ3d7%@#520T+*ehSU>wfxz z=z9s=RSxoMHdDro*yra498?@(GtblZmxVmdE@66*cGks#a5jVHz}lhBwKv4%|KJaM z4wb`5L}tCN%T;{o3b8Dv!xNxFyNYB^hCxnJ@kxuEXvFIXsu0EgJQC8UEvKVsRrOMF zkC*zzb%Vui&R|%`PSRNXfqDPSOVDS6>Ho~>VoC^8jolK#qHbDWGW*k7$DdkXeO)ZJ zr)yhCxYqurzUPsV!l!6m82f&R4z}?bgewvt-0ns6?BH*V{(@9vB6g zXcRDDk4gu2pe;iWmHZ1@ngGTrY7*&G**|v zAApT6KrD8(s&Y6Y&O0Ws;{*%jd+Axj_xp4$hR(epE*XoapY-n0;CT}}Ww^4-aK&pm zP1dp2i~F`oQ(Hhq4pdK;C|7!*(2In+WT0C7XFR4j>(?b6BT~QQPgcwqz@i*%-;3Ov z)vIgZI~@qYM&k3-6YsK>s6zbSB|n_fb^?6&eN``!QNife=%u)g5tBtEHy?`M{udI!$Lr^1H!q)U_~@1yV}xoZ zEn0x3ZH0Bc8Lj?w4OC2y5D zoA7(-39a--q&yv~>{$!7|LXWr??IxQ=s7)??j3TlgfwXuhwr=Pg+r(Ay0oi-XPsUa zAz;{iFB#f!A&)XYL%_6J96%@>;0Y~(2mRRV4Br2pP6+Ot^M`5Oa?KSBGN*o9GDoi* z!-^cSFyh$suEQ~X_rp1!fZsFQbE?i#Tk+We5})%GsZrpEtl!eIZ6il zBri%#WHMl`HmfG3gzR+SY-|E7OEvGcAn|zCpT9??58-QK_Q8^JJ!MqVsxG@a?)r-G zSPl-2yre#ZO{SF_jIdkJN#w&uY8c+%VTMX&G`n9-Cp;2X$!P z7!5K8ZhK}EPLZVQIZnRJgUET%NheOV|Wh!fuOfz--_g12J zN(7Jc|3a>*g6v!Xu0PC+t!P<#+o=8BZO~bD{f2FznB$mwk&v63?gwRosX4m-M~tGeCJiT+peF`j!}J7{{Q}7*%ueAjL!#hfMJS;HlsB ziK*rq;!t146>>gopM7t{y-YeC?{T$M#lQ}mxwpCZN(AP)UCstV`ZsA&pPzjticWs{ zd+R4KAz!1w8s`J3seQU{@6YUP@MT}AlS>$uzQuFybdEBY+z*r1D-{>cXv4lPIJFu$ z0~T`|-K7yIf?(c`3DGKr4MC;}^?gkAmpccKG=|KgKITv#tue>kvCRdd$f z2?qYQr{i;}_=EbNRfcy2kG!*ux^eG45^W1$NMT0$Y125~sL2%ZG0=ci5ozEa7gzb37#F%+Riz98+`_@4j7$*{{Y2g?(o*=?ZR(Ao$4d=Of45tA zQ`YLrUi2SP?Xi+b5nkYEqP^JdP|p$Cx~X`*3K z=5<2(KM=|H1V}WE?E45f2d_cvf;p>K`x6aXQs89WLwtCfvNLD+zEyYstZ+lydo0}~ z#8>oL8h;@)S#W$32!UMVyhEMue<=-z^8A_9!>jvZy-$ei(N(+LZ&e;KS}wc|*jpjo zM5y{U&baisRv6W1_WG#o1JG~Z*d?Z0_CG#+rFh^DVl~EiJ$Zed(5@dsu3f13w23IX zh>0eVudvE_^|Q2&QPg%IMb7=1y}lUck_w{})EF6HC-1y$xmh4P7OcTT0XM|&3e?-p z6w;~H=%t>Br+vtV2A`TrbyjQ=8WO2fE8=LcF~noZQWYljK8NPY|g_k z%;CLjd+5ZKa`GOh8@w<^asBH=mD&>~9SDWfYqW-p7w3Qc?Q`)!=?;J$0FZAJkk3Jx zA-w0t<+uaqr&Ah>&gF%#=D{0e0J5Cm+ZB%nmwNq@H&mU^wNb z3&bj?*%nG6CrA$N?l-NDdy}iFR>>DiWzvm}FdrR~F_;fsOYIs3LAfe1S!gNiQMOO% zh&@H;`Y}`^6iNfzmAKU|aHTM=rK}!(onU#jJSEyE!1XjB@qH~>&@9GanuaRQ{ncHS z)Q?~ifj_j`annWGB!@bWT#QHSn9K^@{GwRjzNYc$dwqaH=5rrKXoR>_s~Fhp+|ANh z&JYaV=TgIHQ(rdLYd@7$-~F}l961kS@FIQKKDx;Ft9Jx#=j}Fs->|#n5@suBt%TYZ zfnfM(AK#t@&>tVwxbrg3nGjF^+vACDZcIVy%ac477sQH8 z0lO>a_KqFPr9*&sSvRoT^0S|Dy!E|6*!Ixn3Q$4uqM}l%|HHO*5T~}%Ez*q+64w9h zzB#Ce7JZAa|H&cMCQCs@Xb|geTZCisYa8@#A+6>o+Ue?f)q~jo70S<%-PGV6?#PCX zg_PgXq&{-%#L9t(yAd<^$5fV;yw^pNfOXHAa&Y2Sc)@@6qhJ4JUO`gX*69pesk8VK z+a^*H*m~F)#>#>P=Y(Lt;%I4Nd%E9%_oW8)urOSZkpEzn*}R$8Z}r5}&-)S1Eu{Zk z9HZgIUB73m79f20{$=SuZ;}U?_sGPH&(Qpb6yj3J=opow^2u5psA!P`03!DlxnG#e znx;5n6mzg+%uPPscHy4CtQM5>KV)uH?0;xT_Cbl0A(2whN;G9;Gq2D2JhAGYv$TgY zhpBA{*x2Q-1qA=KfR+MzlmA7BvN8jV%st>mm2V3Fiv$}Efh zb6s)o)#N|?(4U#$ilOb3*z#rAhq&p$S*heu;O|WbW)btItIOyV*lyOoRDjEuoIQ(Q z0eH0GT&UOa1tkL19J`zA5=Rp}d*^C0F~|xt7}a>WX`~l=nERh^{d0ySCIJBf=eg<^ zD6n``6fYLPYe0xN==88uZY9Vznr3C$j9Bcs4*TWC_4X8xylLsa`Jj>~m9jZYuZ^{w z+_{dN(yck9vX)=a-vr|nX*sZ>VIcB>vQBe5jyy|gslqGPr4IkD39(C>KA(fmcZ*el zVCPQ_hnXjdP-J#b!(zgJo$Y2`s*B|frh}VTc#vlwwnR&Unsojc!yhmX2oa^TzFPlW zU#QF@(zF<~{L+yJVe%a+z?(;2Fr0p4G5+rE{XtjP=*#!Do4r|rcf07h%*7>hCC}2O zS#DP1!=Jvl7=G35@0ym$ax3+O?u32cMoxJ7bg4Vx^`ubYJ+rNhXG!8ROe(A0RSF@y z-Cm!DwmaXa+tFL-wJK)JmAs~?n{>Q>J0r)u%0OcP=hlB_rp~i4AkZp5O&9&ES7=Yh zr{K|FqUoQ@PEAZ02cj5F66zd~GZY%+#<78|x}zet)^+dLb*IX$K2%N;bma{`_?aGM z2|$Rl3>1|=HMN56;rJoQ$TO(0Pz)n_cjec^EEhE{1p2pI98q_`uD@khT!KkAT#xJh zWw=PO+~C^Cui`2x^}V;^)p=qvidXX)zjF5Cvc*(y)11{!za>e-$rk=Y=l_YebPC67 z7twVW-h0Ld7haeeVK`bIBxE(AUpN`|_^88{UYd9t#l!v6s`(6XA`P{6gxL_vcRDh2 zjEYB}HZ_3c-dq!LBXiKjM315aW+mbxL-VU1XNjDA#8Ohcb1vTMP&6_T${xbC;dXnI z6I;re{MZfhBiSP~6mQ+MTb<*xQwtVP=7{6zNfz><-O8T3Az-q)jG7AfL`r_}k^S&P z*(L-oH}xxL7i{3BsXeTt&_j<+vufqU?MV`}2`i@8C3OGXwu<*Mc!SR|yi!5giE3W1 zo@mh|a$i{3NT|9s2ESPle2^w}x4mTt1HIpaz^*Mpv>RY<1*v39b;uGQ!+R~H_-3WE z;JJIt!Gi}YAuBRYzk?Wif-OBjKy@enWQrws|HiUE|7~<1lywseH5DPE7fr0rHkX(E zm*?4=^OpvPb((|P!C0L8R~#to!iPCu@R;AwY}n(9P$9MT7FQF=q&8=mqqh?jMM5`Y z$~dVE0S(ODSH7ksyvChOJ-8h`(ZX(9ijr|^5@4BT3itYu?vl)z5UF!4y!^ZR9KsuL z9^{230&qZ;-1~WPcJmB6>_R7fJeE1^UR>GCDk#~4qpISaTO$Q*rZL~vwCX9qVuud7 zVOKfhnI}J!wVZ75aCgGI{Raq&{Tg-v5lUg^Qz7Sv=cp>L<1et-$^aduRPJ}g4k?_; z)e78kR)`ddM-eqXZDXBdd?CNi`g8AwXBW=)oDRtBJCUbD}yD{?M;8jk9 zkALzwZSlZ&&CanbFAn&4tXuGRlW-dk*b3t-u(W{=;2ao!BDyS_;Oj3$5bCTL6Tl!i84 z7w94s1rK{d<$@LGBdT+^a!1r5p+VMdxKqCM01iMN zVmuH+Wvgme(Prulh$Ht%~Sz zg@%_MSg!@7Vlf9sM1)cO91+!+o;EQl*W?ay$C$3HyfHCaoCs1%(3+6wmt7)hXiIdW9yXt8u z$EDoS(0v{|fJ0y*GesH@f)dEFlno6n9KlI-1XhgRyV1|!0<6|VDjyY9INP~ePC9j} zZ*b@_OSR_tRs)EN*InxyK80}+h{FFbfb<86Se|$mX+WcT_Q}Zkg zZ>gB8pl{pk^}l>wi%evY{%qX_qo7j7$88xrg@|l|H&-+~)vh=Gq={w`^HodQ7^Jm> z;HG{)efPkDkY+TscPl*^?(nl#bI02CfP5oWsXVemj{d_ur_Bz`vG|EwQGWPUcdS?tcRQc8~JvFk~ z1|!9+R4TtdT^XOOFfM<^JCGysNWA1yA{0GSVyIv^jLqE3Mfv5jWb)6bts81WymE;! zi94P1-9qqECToVRg@wydwJYUFyJ%>x`j$=Q8_?5S&cr14z}x!VY%Zuzgv;peGn?Oh z=HF!F0xrK_*vfzL%%R6LM1ND>3wXUd}{{*yOUW@$_$2Nk*97 zPT2m?{IA+fl-ntwFrgka4gGEaBE9!Ppp!qHu{x(Xu}6{B&edXY>*t!7Ekugl{phrQ zPkO|;6W3fzI&87F(zPbyNW#I7BvPt~gop-zUU-MKQWLJ*b}D5RcDSpzr;jOlNs z^_fOnWy2mdZ^##b{2qK_rydBCc3MzMy!~Qa`*-W(dIJ^gFQ4`;hu!ZUF~xkvRX|-> z&9DFAd9``W2IOb#K((LxN8GOkI=cQOjp=Hp1aA0z*Wz(A%EW*^)H&SswfFX~#xC@S$n2e?Q{2Y~qj z9DU2qYiVK{nkX$#{Er;c3?Jt!Hzn1-S)!F=Xhmi-zu`A|myegYsYO zi?03nP+0Jm;b2p&E19py`TS1~*N-0V7*a}lY|1fc0B6J@W}hZV5s%cNwP<#283Fl} zC7{*leJ3Fq1Nro7kIE+rkQYt9C=U-~p)R5%ZZb`q?oGZ|Q7Qm%XY0Z?Y1`sanB6tj zxU8>K4Am=7xN!h3*-A{7#uZsAv2Qt*pgY<#g%cS0G|v?flV|etvHQmv3gVbFp_9R| z8(*`FhZ@6JdLfb^GCIEa&)tD_s#Y~_vo6<$ks@xK{ud>20)xi=1S7 zL#F1R&WQIm0u;Z>RR(|t$+xEh*%)&*8MfwbHi}iJ5AK{!jrKcf*gKhWMB#R{O5#eb zNbo2ZE4lkv!$N4W^CYBpC-b%Imz+?b(2Fz>Du}j5rx1;AVzx4)K>0*`9{Wj>^!q zt7InS@gL@p^5eHN#Y+Zpo+RPaAJ8Y22$llyH%ra)aR58+|Yrev-MMoN3EbZ~zR{fmU{(B=&!tHr-Q`hFUYUUCftyhL8bDHN0 zU(Gt-39AQ|&TW$DTb+%N&*v+4>WxnH@qnz-_kHebW|9D)o~Rj~NYl!kNo|2Zc4YL> z9e&K{d)uYj8WDEb964~En5BESN`0GS`@7q3-t1;P8DHaXr9&if<=KxL%SU*KZ!m3J zzL^(5+D#yi!--^s1T99bO&YzgCbEL`Qm=XZUeg{lY#d(Q8Am5vl(5iPq(H{K9P3Wq zHy}yT%gyhfU+ZHO@KwvaKVJG2pN_Lk!dI&wdV@Jqic@Vr-7YU&uvNYdOnco+y*??i z8S_~ojT3a^1^+QI=EX~xozigbdD2>!I?Air>64vz_`b>okf$Y!#uwXAo&ANx*>hc#TwurT-ue^2IL@@3RhOA%xm?=ou0yrrL{=(w>sOI zNYav)bR?ST^7v&gCIX@P(0>0IUoU28sl6%eZK;(+F`z3VHpUoJ%lz_t-2(<# z=#xV`KJ4*%Yt7?`D8;uaxG%^L%X@zG9^1GtF|-^e0lrsbb4mabn8ZZM}5$I%n6OsRqP`w;twP za=k9MfoNhT^p4YT@W-*z=4YO;p-WiYo^>08)!8c#uOu#IVP{Z?!l8|@#iC-7N;=J# z!`vicnM@d377%87^x~pX8RGtJ)ly8??0@>)8MPgJL!3p`xx6^v9S8*A-}1>tX5;F2^LA2 zGr@N5X6}8vJfVGxw`jrw%Ndb_E_lC#;P(6Qe9ub+hk8XZ&nT1GKJfsH2NWPGZ-Mx= z0+a)LcmDz_@`_yFaEY0GY@tUr#X9I*-dV7Y3MRGe`E?967veP_ym%z^g;<1%{R^ME|*xoltKRNk}Quq~V8$vi5pg>oD78=B<@hEQZS zU7OJ`t^56T4E0!LT3?|t&M>L<88>$i%zi*y+!X()P39?(4YNN4&`CJ{)3R3@uG9mO z{LsTnK`E8Xyx?ihDCD5D72zp_Oqlx3o7BmBmKnmRQWgO5U>JjQi1(EPxt1&M&RA1{ zbt*7Nv@cXvl2NJWu3t!0=fB!|r$yTtZngq~l7>dB(i*!^88+z$AFvL0E?=Vix$T$^ zkr}0;Hx3L}ca4zzqj@t$4x7C64rD^P!s^#`3VF|4mDrQPMT z3db2wSYV46MbV?fDjQGEfR6Tn<0q;8=?uZNcY;n>Q9d{ga?u&25OEK;9+`XE z4b~FhG&8Oo79rx-`P96j ztjw(98M6+Q9?`cx7`W;bf3!*dIUg^h9<2#Cy%S_)t&u|UDTV!=vwz*rOcSkH?g7oW z)Sk}i7bz_g(Jm3smEUpu=uAi<$n49Hb41HiO@SqYMwzG8wjvLXfHXSze%PQFAV~Du95+& z1W7#4K&OsGRzhwMWSM@^`wVV9GvP4au4$ONoDOaSn5rUvFf?f_>5hdZ_p((vClkdl z?oZ46(`W7GdjbkFILmE3t?vshWVx`0*|{>uiA?~@)c8?)2sO0vxyt#k>_MzMt;<87Z>EHvX%4HjOi8J5IM`(E&TcIHlz@tcGT?KKMp;c6r`z+Nv(Ow3 zF3k(JNP}xXr)knil{>jifdOC&AT#Jr>PzE3vwIb4z)v$IE2E*0Pi^OcB?O*Is43Sb zocZ7lX(!yQOP!>frBciSDkRIMstP~#U;PIFKyv-H*%&|T1A4?oZkq45AETpx{uAB> zp4LTrxxNPK!>H5p=Te-G3^SAt%Xc*S3_#rO{gb(SEg{>Z;C?cXJKIe@2@gtQw76Ulpf)Jm8z>dJV@HurJ6)1V+!xUk; z)k7M}3twspTegjR|9GQ$3f(031o{Abj~e(9n`f4e`DxXCOYH8``PiH>i9Ve+@QXi9 zGD(zVo*KScGG2h*^wjFrLF#I4R-Mx77M#5>x7a=TzUu3nIk--MSLBAmCbp@nQQWTp zeMd}o#Z1#Zost1ALo6@aYjqg9_QS0vbwc9w;5s1Q32)fFo@dpnU7avfc@y8eJ}^?f zNdWY{P<}aVEYKNJoLmo9KWyg(kMCEQwX(-R%3saexia*8rv`{t?Dldzg$(bcH<5C3 z$+yx+IKpgIcL0`_INC>msytCDgE^Ae=7qXCu+no3VB9|dTo7!~wkJ)8X_Xj){jd(D zM@A6h5Pr{&#LQHSnXAfuc33yh)h;nJO+vz`TOSV{%#Qm?I*B*5x5vK2@NoI(wtjtk zdK8VQli2~GpH}`{4asXm=gAr5+WE_)T4?jvCcoSRIB!Aw?|IjBKYMe>Wy(DM@6g)m zmC5A?9}7-4u)Ix$@EI3aM$?MoUi{$*T(+201C*MmHOITzz~?jIQhOcQAV!R0xCs|zPju7V^&uHmDHP- zLOYeR5Lgiv9`&v9at}fwOwZJY;N{3_VYjaUU&zUC4_cQX$`m#HVRM94-(gC1_NHM> z&j{{M>q+-^;BA-3dAj%!gQ^+Bm9JAhOD;Vl`G_k&T*fc-5gh=L=dp6CYt^i&evXv| z(vDZ2tpy&M{>OVZ^IyL$^Z@;1v49@>3lbaoPdgs_641hRb;2aXmpDDwtmb=pkR-2h z9YuwCYu&HIZR7d*8lau1rN9&9xjVj4Tf%7;pvDSZ5=; z%NPsIV1aUVCR19C-VOm2$u(~CEc0NeQ%|A`5(k(&dQgs3bd_mip6T|qT)eQ&I~mi* z0|#MSlU1EqGMfLVYvFp132hn75~D6NuD@wi>lpt0lTJR+KM29~Ws2CTeDwnw{bv61 z#pc>PyPggVgO5h#vJY+qOj(m&vRAYqN`-jT^<0~OchCox_ z5Kh_7&Mpm?FaJMhWwk6fHZD`RKy6A`u1|-(c(o-bhgl`Cwz4~%WAyT(Eo5NGkl`L9C!ZVqOb7= zkdeiTnVB6O|KOIA^i`V#1&MyvFWW$$>@IbY&-2KC|3@oxx)i)Dw&mM=6-ydAW#SeK z! z?IaFP?cXt9OqRnCcD<8&al7bQ+RdjW{Owag0xqtMw7%k|T?^6V?m(U;Ix%CpoK!)> zu0l6x(k#~2m`IE|?`7b*CIFV}o2v&x&&BY1qWW(%G&EcpoV4T49m*0j#&Al|BeTTZ zf_H9T{y%P}i;@0rX#43$qq5I!jks+2dfTD*7yZDVtAo+Nr%wK54xEux`9|xb?jH?k z9(~bMNF%#pT~1{NdIng8jn3@C+dn)2dx7A~Q~tASnGl>HuP8Ep4%%Q4wIhOuk)s_RrI(O3E(xa0^(vc2G4$`-C$fV zvIw3`)Ldtsaft%jB#Hz!ZE_RMmj`n|HgF$2(C!16-GC^|j&`{c>Kv^KG!NR$iH(m} zm^C*JE`C$?4geW`(qVt-G)~cac9^weYPFE>IWPKeTAbZP#17@`y){YWHs3-?;KcY? zTzug|8vd`9xY!=XrC-AZG+NSUO}rx}zxi_Qdwz?4)F1zSF`0QtO$gf~y)ECXm98cG zl;5Hl$a8RsLT0!tJGv9#_IG`;TJ-@+KkO&Tm;)2rJ`|$)2BPe$faEZDcY-I=R1MMV>RQJ%a?nGx&XC_{e+YF=LxrHMVCga^+R1qiy9mh z&?l;9*rM9i7HRXxahYZ=hwoK(}>d zk4Sca|7^r-l8%8ZZ_T`N{mOfvtymyU$kP}*yd~vu325SVGsb()19H#mQnOeM_m2}y zl*WEtMP0_$FWaR)_~m=z_ltoR=gC^9^dVfI(?ogn+Qe0#dDe@?s|Md`@_4|KV^q$i zLbS9t-3K_~U$NX+m#%#@P)YIJ1*r3tj#S+1kSU`E_xwLLgM!`Tx)34zMcv@!pY~>T zZUQ?6D+NWwJYr-6QW>BtlI|oilk)3>+IM$Vsd#4>Q)WYfhTdnHkEI`s+eZPSv^>Q^ zJ+`@?A>&Acs^ym@V?KSQZlf*q$;E1yagGPy3v@x=%;HqxDwB6zx_J$nw%*R|^nmF_=FB?8*0>a8ac#yj@T=|3m!E>i#kzU?4Nr8<*i8%D?_%dd;N z=_<$h@8hTQ-az>``17pu9y@Rl|;u$2zhRqz%)?Oy$ix08u zO=d1@qQkR{bvDQ zcFR%AU?$06EnwS$wmz#!kC*diKnywx_k`N`15W$;D}~sbcYz!L8043QedNo(8P|P#clT*<#kD^H1&|sSywt^jLU;(lr>B(3aFEBMV(f}-W-jV$cHD#vEp9D* zN2|u0`1$9lEBy6f`pjGaq_pmTPd=k*T2-^pgT-Gc@~@5gOFK{N^flRKNxRl3Jup=S z{+wd%KdUH^r*Q~9nHCuBMjetrFaLQeB}`O!c_VRw0KG+l#)aT%v{QzZMy=zq&RBD*+-e#J^OhIHvzh3)q1m7}!ri zbIT;0p1NrlUAPZy!f*{q<)#Z{Nant|lds2fj0<0sK;&B99Ir%t1m;05kwy9!5TcI% z<@n4saysaiV-0p}hu$i7*WL>nFNJK9wiazq!Fv9iB(agD;&!idC=T#n76f)9u;?uc zw?~$jJj0Xy++05D+F`%ftg_wRo59Yh2Q-HQ>YI>Vx$O_zNq3zzwq(4>OUlpLJfSET zuI8aLKs2~6YTHYk1YP@Cmv=R@-dl16@Ez}M zeSnIHc7~I`+!);!UppqqO`LC=@eh5IRjYZC?(rH{6U{dIJjG&WQS)&OA}YyOb~u9$ zHo}kh(W?K=_y9{~3@W*V)(0Hn#eNk497pQ`MDEK#N7Fhk>qa$@#a`?@kZo8?_Ma60 zZ|Xur+<%rKWTh&R4ag_S2h{{@c3y!C?Us7O-HMrseSscj8Zj{8ihz!a3MRun%j7ur z*;%kI#&1nTu6p6mC|&3qUtfk%LT`PXEn?OwK@g!CTMbuaU^_#iTQER@*PF^mPZfGb z6kE?izncq4VL?6LtklxEvnX^jfYA=FgEl&^$7W*p$5~VN`^{@orCw{5swu2X>TOL5 zr@sn?BPNU!%%22AHul=rSRJ!|?XMN|9X1MxY1_h?0(ZsKY9r4Qu6K#w_Xejd`i$}${zD?Bynp3-Mz;>yKnWO&YxA1s>wBLBNP2RqwK2+FW! z!0=n`qw#I7j@YzMuaLws7PxgD9l4(OA!v*WH#2bS8z4mzqQPyKz7X41SVHSm1g;c_ ztD|YT2y`fJmveI;_PbrLD2dy_3Eh)lBJ{ zGcRN^aiS|Na6W|3Ky>Uak)TJ8k6gq2uhRBO5vCs6X60R^L%;?mU9t2ob0Q>Nn-di; zFf&j7ozcp3abXR^po#JksX+5SaASXNP78xZ^W$yf zc;yPk<{<1xJk&YpGTConM*}(<7Jvlzd<^VdP+4Qqmm|mCuS^+IFBwXrigEL6jEOV! z%(I!eq+{7LI(!5oWdgQ95zvCSS|;)&-`9)=dgYBEyOSB)2&-CltVBM)>QxU7La!{5 z?y9HqAX>LY+0s4vWL#>M%Ie4W{aUBvab!YOodeTZ5Z1K*~XG3j2T;& zvF{AVjQi_6&)@Ytzw5sL)hjQ@%yE2=&*#0O^>J2Z2He?QDHp*@y7Bj180)N_If};b z3|rH_YUb+>_~0z@m};I&u-pEAkz4(`MNA?ML+@wx*2b>ZtE%H>E2}D=tiTEMa~SQE z^Wxk%4U_Y&r@v34qbUk6A*EY3^Qk$?&)~N*T%O)8VkfgG80Gff)&d!s~r@ZBhI=%h#|OuzUO@ zQz4AYW{j}K_u5|Li|wBs#r!q&`R?-apnL4e-DB!|-@RtOz4>f^o!|8nOUq4%dw~C% z@Yt-pGo$h|U{jBxMlc#Cc0(@!N#oI6)0QG8)aTg#`We>88rbmJ&_S~+$TfQE@zwEn@4~`=xgR+*eOAxS^-uMJgoDPcq(bn?!${oH1?n5Q8AgIv(?UYMeqt#vj zZVNG)6<7f&7Q8%4C|iGZT9q*$`T0vT^bplM7OoBi#g~vBfogpV>hVRUmlI2)$!ut( zH1x?4IP%`#Lh{)t#q+D<(eB4qdV|@Eck3 z9GSKyZTnMPgw&LvH0#|e0gv4dtG(JkZgD@|MX42#fs)|uC5rPtAtX+@eC?e{QBX!! z7!Nb{T!GJ4xidDXk_Yn+#0uCPykXo>YXV|mO47-f?BFH;FD89tct2Y64|xH&@UyXI zkZw>=RQ|=_`5To*&DC{_Zq&&kS$v2w&nQzzNzphs`*<@eakIAI{@*yqJ54orbv-LP zl;~4Ve>Tv^{YU#XZ8zs$ekJc0IruoG z9h=*W^oN~Ut>y=65_y0h*;Hk(1mJPEB()b}y=IGM|dnG{l|MO|`-RmB6Q(Xcc)t~IpkKS1$ z{NygL3*-xjy|!u^ASme9*e)d5)Rhn6289N0UrP|wj+nA)bw<$_l`jy^Km+%#8Gg}Q zZ;!PEzw@<>xkk6e>%NQMKm85T*IqnCa$*9kX>_IpuW$PWOLEs3U~wNW~i#*DzgAyu@6-JjMpR1M2z1CBI6H zH3BFTko7~rp7F^BJV37=?eZY);*#Fb8%xqHDfbJDnOq7&)x27Xs#ZUD(dOep%gLXdfX_d}(LjAUTu0rH426uI;HO)RDcatu4%E z?Z&9Rs0HTXUPlvQIRtFZy~!E0IocV>s@(Aep0?Pu+iT}aWtOvz?sh8kW`pM z@!85UHMg+33@^XzZv>k%jLLf|40yJFynBXy_|436*x36O{2JY(LIY-1L5UC$`2%xd z#Z9U?(kb(ORwq)wj(vQ;&KtS{zwN%K0fFfEWdj4OS=EE=>h`Qy3)e9W0YCsWo<#n- z_1hiB&>!^=&RdL@2sC&*`}mBjh;qv6Xzgr0?^A1*jYZl}qf4mMeK{$(N{LxUo_A1v z3!RL&B=>m+s%5-&kuiMw>BZ%Ht)rLlU-aHnc&&<$ zk#<&F2dwHOOZ{U>1XEtJv*oyyrB_Vy(DXY^ZMgF zTQ8{9xCx53TP_n%n6<2e?4FIrZ{Mnako*?@^ZUKMh`%0wR-=EEZ*uST9U zTkYBF5i-|Ff2{;99099GlKLyn7=lmz^wo_tPV!CLR<+o>%5K!V4ec=H)t6cseh%9j z;VdWDS(`P=pZ1;;dwHvT?$?PGxt__6%H-&@?ub607$pU_&dsm({!EwcIuhui0ef%V zrOn#sRv~Dlq`|$tAcC*^`fp=s_${Ie&w~5}A-W8qasetOrGPsZ#KfDcrud=i05QRz}A*pa)PGR5-~f?!~Hw7)P=BhcsgKxp|x`7?eR z+8Zb_jgDI)GwGf1+0Hc9Ys*?4B|*;Uo*w{D;QDC&;|(Is#oP`4lZ(-r%3FVS$Xw!A zu^0O-*Rc~WE-t$OPM%?&0r>5&YF+MI&c9Cz(R@?yXido#8-ER6XeDSBsR?hQ{(#dM zJzS$Fi9ymF_C^(-*%YVfvhXF06FY-N17LR)IbG$IUpovT&# z$8r#Nhd*MeJwdi0X(^oh1{;uhiy?Cx6+Hhm&UW=VH0`dxyCf}WqZTW^z2CJgGA}Zu z;2X#9ZeuZ0{X3ShI#_(g!>-L5Eg0}j6#IN>acSW49IAWwt91FNrggXfaI7A$1WVzOx<|`;tsS>7cKefk-eZ1!Xsz#+s_N>F(ok4+ z_(5d_>|rsj{`=dyZu?u$YT;zrhbS066pU54By@yL^nZ<0fv165?jq0ikM4^t?|7xF z-{pFbj!Ygjy|O{-WI{|!_eDr_v6rG)$68CQmjkl((#)Q3>8D6rjdYnRXoNsgF%Fsb z0?Mbk6nA>lclJe!+rsDx3`{3(44oR zicAMmX17cHHXRQ37mHpua<6kSnhhT)Go0yZE$Vgc6n!x_%n70HW~~ZMV0QP2$liKY zy7NP`vgr>Hrn5%LE~@D7UJvU6wViLjq-Nz~HZ{c(^fNkl1H4zFr1Ks> zF^uJva%)iGGA@i7x3tK1{S)R$_yYsoofYp}6v*J#8 z)TL7~NGDJ7N6DG`MEApskDSNrEy1o0JVHlQ<`G7IM7*fJ10oW3NTJ=5k#o4UlhwGx zpo;cFk~q{1CGxQR)jK!>wO+sa_P!W*I|?|96%pumbIGFeg7N%%(VBzhYvs#>k7)z; zqvo^o8OSm-Ds+q{-@_V_Skv2KjT!KPe5fj-$4upHZ!d56+b6lkKap+lY=LvWF zXANJiaZ&8fPz<~M{yOJ>ZYK@t!b|H@&G9{SP-17wd3IS?DY`3RvPu1WYs7h)n9bQq ziK(jg$-PZ`)4mY;NpxUc`K8|aI=eBDjb@d}Fd?Ny_ARlE6dqqn>va_)rQYnJR;AON zkm*Q@pLv!blx%oMG(J%QW@g$_dUr6#D@M#LWUd9hw%^R6B+A_Eq3ZA0#j$l%!CU_dT4#2QmeE+|;BuEGt=@WAA@FwNi z3E4y@)U6h)@OKteu2;>(l+X7+@Q+x#Uh)0o%hBieb}Vq}D>s9YG8-bB{*3eC!UkEF zb*pc=Rr{I=KWr9SMCm5W_JvYDctG6yn&l^|$4enZtX`Y3B(l86SQwe~Yo3r>Ry%9m zypx3&gSBU)S=C22>0ix9!lfvFnf=K+8rT@Ihh=wl6$an@Jfp?kLCHx&JWvFY5l@WAAO6ko1I% zM1~lmD)<~q41n~y#AsR6AYIs+I7u@hgub`aH$&8be^1Gc-_j{u*94oHy0Nh*qZ0I6 z8wk8kYmYqKH=1=#lTsh?cO?k3WL$GI`9drxi89?I)LZW?ZCp5pH^ssSYvr^TB(;O0 zT>Twdk>lm`#KFS%q5-_Nhiqb^uy#^wtiao%a#y?B(Z!`K@1y+$xFm8Dq8Xav0;Z*?KzB1?m37QNTUMx4(8cPy3 zzo+K^CWJn_JVs=KUV7OmNAnuKxLmI~YCi6Y(M!mM>sF_QFe+D;nKKpMHEXg&av)2s zBXkvxB+@nX{7D58cE)pvFUj7n@lAATKA>fW z{Z|S_ZAW`!;2P~4R}$GZ2hS%LDbK|Wj-LATzC{0we_1Tx9vZwO! zf1UYDD=E&?PSM;0ljI&Xd$l@*_2iM*JNVRW;>qcJcO50(!hc7#2r=JSi=6K?nUJ6r ze}qyTlHTC^B17IxA0;&^xs^aCz3e3S{aPY%(8-KlnT`|(Gp!CI%i&YO$CjWr?D;a* zUO_!*B>-)o*7);mMckKeASOs^tx-Z*}@Y%r36Y6RqVIe?F zb;b2{W0gOt&{hBV)c*EjanbZ;++q>|Adc$P&pB!lAgYo{!l4ncJf^GE#g#Pd33KXp z<)K)RF}?wTH)HFYK_PHvE|d|jdb)yWQkL_~2ibArL>%Vnyqg%w)HZX*sVeGTy?w>= z1epF6l{_dUGQ=@8?R9}!JMk^+yp?SIRl^2y>+Q5a;@12-PJvLJ0c^Oh$cVx>G4(oJ z3y62>jP{zP{zAd*6=L6RQ!ryy=jq|nB!8J_{IJfzdSwr_Q`d(xy{IBH*ozyS7M;m5 zdHIgtGWhh;i|uyt31s^-7uEzwNG|+Lce?4|U)QZHM$#5z#4S#%{A}?0H}|UK=kZv& z4Rz9wV7hvrz~fVZtSv5DdIf}qYo0y(;=8m3h#7-MfJGc>j{usG1l-S*b2dgR+}NT( zpOc%9d(_{AtgF8&3F!(if(vHka1@zgHRjy=aPa!n&3qW)0HD;ACO+-*Aja(B%HxQaA{~ zqTv{i}AyKV0EqkKm3Xr!L36OFAP2#F>) zz1*=#2Ah^hne8CbQBX;Hq}YMl_oPYGgVJ3OFO5mv4mi=U6uG@{cBbvhJtVyJ1@pUu(Hz0~XS$B(>x5dBbJNW7!a%&xnKub!CFJdyj`rL2e6t6~^M8-m zeCtuV0>pEFTcc4EMnwT5FLu|?doZs+e2Y|`{<{2PNlq)Iu0Z94s?*AiC;xlrqSskr z9UO72I{?g*)}a5WpqF~4=ji9{$n1Qk!mbW>| zGroOxn(m#8nD*!NLb#dR4pWZpnJ2;H-n^#S6t9TUA5^iYE@b3oi^T?4P;q=h=;dE! zbx9MGH>I?ZG_;mvuXs&Yxl4qr#0C|U1jn}BANOl+KR}8o|7qE5AA=2-UfIbU3oZz& z1faA6y(=!lK6(e*=G~=uD>;|;y8NR%2ec}|mz9DRHGLts_{>%k1&GMcT3x3&WS!;f z$t#MrFSoUJ0cwBKg&;q5u=qeQ{%|>^pq|(%w#BP(>4vugoe5v6yw^5+QfX1dKij*! z+AXv`;c*dS#sVp3dHb7BPt;32Yiy~^L8qN&;wkCgMXj4*tg;~_b-yu`H%#=B3J>i0U{VzP47tARgQfxxlawgm z%@gjntqAG@LL%0_#R)MtX;-OKXxMU7N#Vroj2JGgO ziNNW5H-~FmvabrdOC_(0k!JLfDnFl2S$(&uc!}66xc5ec1WYb5K#r&QP}X%UA4u@n z{uk(T6{P#5WLUMD=;1B`xMhoD*ivdsq*_Ct``R`Cl(+h+-JQM;sLGW-u0mr=%9d)V z9>;Zx8+3hgTiJ#GMA9R+Ef#So6Y(9`zzvIK&EQHw{FS&L<^upa2`*k zH!gPG@Q4ZKSpUlo77{Gwm-@W!pmvmRyyq;x2?&-TzjNFag z^-^Xp7H&YL-gGc+1RS&&wyKntPR6mHVUuvOkjunb@bU0}CV*#LdY!c;QV3bM@%HRg zy(^-&wc6|Jl6hsOjpF^Sxr9{xA3a`!_I_}e<>}l=+KCBukhvx4k5SFI?O{O(C1#EfyJ+=fKKSs9IG=qom=0?}Gl+*f{{zr# z?aq88(xhVB_v>r(-JxUOwS#z64sSJ^lADvr@1w|VY+`1#TB%a@ze?@3)1-_I@`2{@ zzeY?^$1;Z@uKbaD7IHdClj3^_lYcEPJ&OxXT~5Z-UB&LL9v`Bl0Eoq|xW`1wvSTEG z(y)5$_!G9nDpOna4@U1KEGirH9Uuz6v#*wHo9egusXiIQ;or{YTKCmz4lh-40#1e0 zp9uizW`wG_B&_$ALMS?K)~2YR*KeVr`jR@N=XK&Ak2e#lM5cDCKHQU~pIyIodM~kf z+#XpzMKxYFc~(}-L}Za)aHlOx?rGV@O%>bV&s14Lf~Uq>i#z6m>PiYs3yHRO(Bq#~ z&knz@R1Ln*C_3;B%Dv4kE9J7oeRih9_)gdTf+OIV9f812zF@rJU1Pl`F0}Nb-X*o+ zF+C43B7F?RcF)~>k&q->`dd)`1*bgIH7x|{Ku5FdL&dLRE9F}*zwUf}9&jb^iKE3a z*l9fT&lwm#J1S&hNSmwcMvtu@W9MxOOs1Hi;cws0;1Qol`7tRK zfoVwYtzStY24l?0=9nyyxhHJ?O)v(!Kjx4&QA+BB0kGaM%RxDxOHnVoIGnh@eFUMx zeBY)nph|zEquv}0_2>2$sh^c}QUL%ZeNtgH3kD;DMv zO_74#=7j`08;xB*k_rb^5`wno&JzfP6K`4Vf|jiJ3V`;CPM%HWO5pN{3|L(HD(%;% zfH)AO`O{bXtj4fQSnY~a*8T$_HF0*@5oxPMjhi+&L_d`|V-3?_?~5lp%Ct?Elo-27 zV;I_~jX+>{x(Eo~pI>a*B?CsJh7||YEB3{T0kxX8tg4+{2zP_`SWUf!X>#}aJqr+V z6aGup}rz+b?&CF&@J`pm`aSJw^|Jf`FNEEIiKEaoe=LW~Bo$bkWi<2p8FjH{;wAZQ*Upn4L~#<76M9B|-Q}RlJ!gy> z2j*QVD|7H69nn@tFRFjI+QU%~B&)5EUOGpO&uVB`n8q<6B%Z|YV|>Xw1?L{o4u*2> zf!N9>pK&;`=BhQgU|I#wSv8P=3+_;-shZ>KTU*WbaI&3M4Crg=xNZK#34@xZ)^xu< zZ;}Rxjn6heBcx2uKMHUGF?b}8gXNM7K_XhGcUwVl%6RS?uy(qg(%wj~@na*pq`%+a z745gp%V6;a*Y~0dARFn0kg&x9b}5Y?WSysMEGj-AfLtDRve2mwP|!$1##Q!`B9;YPk0ZyIOJEg*P^6t z3q!t1$-PrToy%aG1UG64ob0U-21-+=Ktyt13j=DVL=0MQv2TV6tV^Q#qvBgDdj3(F zgYI;9hWS+p`K+jl9QrU4dyj#Sz}znw-4rFldSNC*hf9vj$$=^P?iF*4(d3aIA^XTb zIO&;8?#TU5sK~z;x-_kFQdxSw%&z^-DMqfgLutou(S)=<6I>^ zi_o6LKii8#KwuzZBnY^r6MubwbQd(tic_(MHsbxPdu;`WWmWh;5UaP ziT$w~TXOo-9KMlxO)KdE@W973{P9dALlh;Nvo%@WDf?cjMRyIxPSSNCbU1ZsvL?cI0Rp5S7Z#xYQo{f=Vrh6-$?Tt4ui z%C3r43$7IigzSFG@ckDe$vUrHZ#W^(ClQFU=^V-MeABY~2sm&hw7tKP+_n!y_uAYp za&8lMuIhexbc#j?&8PhG1rUzizpB#n8b=Xbmj=`Od6FoFRl-Us3iv?xt)V>SKm>Ry z;^GZKd*7-k@^xsvQsC|+okA$MvLteUuI~Fy)OM=Tg+sT?4`u?-fg_5(=fCA0AnpZR zC5YJhkw_Lz?63B6iXW#cxJ|q&hwp9V=)BP8RS6IdKCThN6TbxS@Hq7oVh<6Tw@))J zvTFCx%hX19TR&F%8Q}JOg32bPsM@*cor4_X8&TouRZbjk#xA+k@Mqpdm?t? zjn^7cAC2){w}~Y5#9g5gx2m1PHxiYEz|Y~H1Ek&<7}qF1AsrOvruVKA+R;?3z68#q=qQNz$OAcYaKx|4o08g@+4@Lc&4jBzzWWQ>gWGd%<=PRgXu3@f2r6^vdLB<^K$L#!%yM&7;EnKLIu+36 zA0PmD_@7PP=)8 zAUSXv#C`TSymTHnLrsW|jF)!R1IFgKNXh!P8!XZe3|F<5%F-WweePPu zd=y8ccyt)?ClC%72?|k5zm6a6jXi!z!Ul1Irc!p=$xQ13$?7tQ->9-C08-LOAfaLz)hyIBWC~^~_QJhj_k)Goeh4l~aQd#6&EEpu~ZEO8D zPXS$Kva|nUr*Fq9xM*$e71y05+&fsns*NtSf&VML*XlS%B9Ztw@3F4bGAEC)H42VJ zh|LhYC)OD*-F`H!g4B|nQNf-rc@&qrr@#K-Sx>u=# zLBh&HaLE4F^MMDal!Vd2V9L-^dyP~?jQ;7raZno?0xDTLjHCkYwFY6Xlg7`-Tdw$n z)nU>zY{GZYz@!AGaFh{s-emj30O(qRBfNxqkZ~{*?eUq?GH0LWDar0J`N+JULX-V~ zWCCVwt#-?+ZEiDV=%(-Z=0@3A2>d0%LvDoUJxZuH7Q4RhN_59x(qq?e+WsDybj&7* z5ZX%grbHoaBcC3fo@!Uo7|;C|&2lb-^#>c;(;Z3lX+ruf8Fl{a6Aj0G3!t$vUW@z= zQ5^5suARB>vm#ot&;nA2L|%8uA*H1DZGHjRRJV+cy^3R zDMdn~yd3bxEy>ZXz%o)_S7+f_%`Nwiu)>_B>@)=yh)!ZfULJ#%lH?9)YwZcdYxB_C zC)vJ|wDbd(6~y$wgire4=Uqz;%pWXVK)w`BaP(HhE)^pJqq$_%s5kL&Fk>85(K+(-VAbV6a)bhV!b)q&4J*PX<(K=iwS%`f`#(9qE#06!mIJ}lg6Mu6Nnuqz zaWFbwz=sLw0=QDk?C&q%uPB)s_J*)f8?!dSu*$ZSH!NT@81*1k@LK6?+netd-);5~ z_6T@95J2%mCj-7(WJ$>?y4(W@SiFe2V74amehln)%wOkGD?xTiWGj8@+o35r*&+CI z5YqMDb_#dtB@!$`yci^>D_-`5oRmW zO3KP5-pgj%Yys9k5@bY!q@9N)MJzoVckAyy3!G|U%(p=I@dGoynDmrsXjtkdcw`aJ%~8(rKTeo00wKt27#`KWzDDf)XhD*#w>6k8Yf+J2?co@o z)YyPlg1%dTiX+b zV7x+LU0}(aTor=ohv@eg4_tusA1I~L0%so{h!R)tf^?!KM!A8nP#S|Qb@hlxA`kPP zh&^&E)*$S<$IENlbei5Yr-fU4jQ4h($9Xzx416_+S2mU%06c}d_C<9tSjNd{JWd@> zULLMrT~q0EP5NpOC#|oSRA9oET56YItDPi&<%?*FjY1)6bmR|66jiIGU5~4@wwjhm zhwewSLo)5ya=YT#$d)^%BN|s#DhLq2J&h%0|JL1mYsL*;#z8H>q~KP)uGCQdOVVKn zw67^0cU-M6M^lYT$EQ?Awz)!qb{1gIjOW!?p!gCRKp`de_`LnBuHKA)-rBjx-V!~{ zJhU$*zs1@&X<${fOrbEjRQxiL$@Gl4*%A*z4+ zVP_eE8ShCJ3S-7ztJB#$V5Q>!b;q9;WtZ$IpnKPr9zja#c6wT=ez7 z5|)B8wI|aRa`GQWG>01iAUjFI!sOJM&zwWws%Nm;vyfOY(fqx@od*s`t)~yshc0No zzK^2JI(FuC_*9$Gpf$~7g;SU(mjGFBx$K*Hx8mjy-9<1atTE6Hn^;Azg(C*O8D)X~ z$+_W@EXjb~HETHH|NB0J#=fK9ofkOux%FL4xTnw`AS9cFkDnF0jXJ0B_^ZiX5wxxL z3N&DYal{)Y02k7ZXYkisM!Y^o)YcPzRC}&IV&mcn>8TJI@8ywO{;8p?=y|Nb%2AR9 zj^cM_IzCW=Ub1q=-D|GbYX4dV*YAV`2+<`|{m_7NUfMxtKDYHFFJklEgMjB~h+Cu5 z1rbx;8cUa5)0H_2$M1#8J8u`Z-G5EJMtXh9c|3(`dtY=q-Sxo1lagykxuTy9vatmm z3yaYzx7046d+441h7+4ITln%P^ir_k53R!XJi{*hUT^C)5S;O{tk7y!CQqr=cJ4d2 z^B{I6rL=Zte}A6@Qo<^<6Z;3QprxvGO1ep{iPl28d0C6p#4jLvh~HmIJ9N-SS|M6v zS?OrZP)SjTH}I8Ha*mEKzCoe;n&;%ik934UqNBF2KR2kmgMA%hFL1wYJ&#Zsy$H1R zlkem}{s%t|6jsgLa%ELW7Jr?OPlbL4*bU#1`h#Goqi9f-pns?7VJtj44w#p()iw&* zncToYF@eLCuFzw%U1>s|Fj_}R{h9h@a2xQ_UL&Oe%^fx|S1TqJ>tMYYU(h(=9<09a zxiOm2>NA`~zOa5Wk}b~u!j>qq305iZav$iU?EOC3yq)m)$w|4tlek1RDY1Prwtxn_ zdo34L^j`Om-v^abO&=)4##%K%f8Y~jYuy}Xv_Pkpwu-UpNO=ja1(FYiR2vC#KD7;1 zK3Ri~;m5d^IqY_rX!xz5URLm-k;5kU{ajIw-a#O{)c%t8fg5f+LovsWIhhf4ThIxO zl+$K|*n7)EUMXB|5IRk@p=gbJElJe428kYT&ZU2}LVk-RgSwfH%h0iVKYR0S`Jyr_ zST+Y08-Z<5w$i}abBB6kip!sV@scv7c(Pc|8;J&SZQmvukiF&hiqnn*<*Kec=(U0_ zZ!p$(5M%#KvCLw1b4G=jS9~!&?2V@r*jLeq27uR*#@1WRc$B8+c(4fRisH7f0`(C8 zGBD8w?>Wr^9#umr=CZ0FpJ_{Hkf%9|oRx)XrYxKb7gXlmHSKjkyI!(5Ee>gwgRS2> zf7qL~Isclzv@?kenmgvafAt|)7eN$-`Tn1V<3eLHL+TeA)BbjyJ#zhZ1{4f70H46| zW-6L4=t<=wBZ!#bC>vU8VzX6DHkYuwbaD{LL11UTfbN4=FE2>I*StUB`L0Cm0)>6 z^fB8rX@|QYBQG8lSn@?3f+z{PoTW=qPDAnM4m;%~}aaw#NAaD76K6(bf-}*M;y8}V5di4Oq zk1!B#CXH8cRh~C3_o#F_R?@?@2l{F+?qyWEX0{xcVDL<5uXmA^)!;(;a?kAa3%1{4Bx zRO&Vr|8UnoA1YzGBkBdzJtAuqECu)2BPa}lMhg0QDEWAlmV24iTa@mh#jkoGWe!Zg zw_30#5e`?t_rLL;e6rLrR?-8x$^7WL70*n>g_1ZiTfwQ#BtCU51nZgPa%o|qU^7%8 zb1+S1fkn;DP(4$I*svhHa~3Ufv`{X3@wvC3z8}o8?l2$R%x6Jd<<+527ryoH`Mv4j zLbH);coTo(_1d=m7y4kw2hY0@4{xs^8%Agy%{L0Yf6NQXA4U5nef)Rx`*wGj}yyk$*2rpIVR5pmY%lnv=vSDj_j0LO(MU~MXJx-dBz;h{3?#G~pcJ(izDA213RSgwkbLt7SLNbs z(C+Y_MMW{AD3aC|kq2@`r!`+cwxs*`;F&)%Jg5kgtaEVYH}_@p%oFlnT|$vwgjz5D zZEc)!Q;Pr;yM9y~`+eY91n`%(my{mT@G?ii7TZhI9nd{oBunmF;4VsK3QS( z;o8LA>CQPLR3z(s{cWG_(v`l!g0^YJ^AbXv(ZcqAJ6)O4EiL|gTl4*Q&~B3_B9etU zzq5z|wG?Oz^O|^xCw}9(_5zqUbE0?E61Hz!ts<7?uMJ^2g1FD8E5KibQZE?NWhT^@zHWX1MNK~4<0cPAa$tlFm4Ipll_k`5=gaZCP{ zi(;v_(ucHnu!h=W_4Z*X;8hw2z=z-9GOVm z;Td2BDy0c`?4>3lCe>%;zNZ7F@j7Oh^Ft^HL)YF^>fu|m!c4m>l5 z@*ULZVmW)e;l9pS^TN`Mfo?}U&?SJt!u&o7y3yvg?WMunlDToS9@>X&FqX~bVa zc0meOg;Uejvwmt<8-oe@De|1a*L^?Tmp;Ib6s~=|R81t5XF(>}<96pl4v$dM();JK zNjj6PEgp!mPtIIQ?w_u)dV;oa(2GLzc-iYcu%wnuwXjaw@90ljWhd30_C@T?gU(yK zQbW;H*aOVXvU4}Qc|cRW;KtK&wEytDhh@xL{JQUc)Q8v8-}>50+|t%JuclLM2cvYn-q*V9vvb4%R){6LJ^EU#f#3@;Q zK<=BNx*#?upIK{V^YF;;a)F6qU+*h+IZ(w*tMqVYH%p@x)LG`h)#Ax8vx*JMqJyIE zl)+#j!5<3`EF9V4;O~1}_O0pf&Kd881ot}a*uhactW*8!rmQ@_F_pi~@*@Y&f~+dF z@mjnxPz*%H|xm@vJwx$9k5>?_u3t?bL&S{@x;kd}sAk>73`IUp5}GARV|Q zy_uBYbf>DBQ-$@_)w4S9)?Bjsn0)2qkv!KtQ7IbVK859pUlgOP{smqn)Yk(`6EW%JXEV)1faXpIx z=vkt_{^;u~e5EUyy7RYL`rkcwoHD2|;QAPP^>&Wmr$28WR;fK{FD6b`!b3@jC4X}u z8t26xIV-FAWrhQ*83abJZR5%Yx{$>2#^(qZ>Sp{#AgZD5&+O_9gH{`@S!~$bU^+SxQab?u3`T}y$gzAvF$1`sG?^Qp zIf*}{?$&*{^~2NA@mZe7IGsZ%-Z)RlbO1GYFuw|*nC(g$$hejjJ4Wj0+~UG{KJjk3mr0BKnyY;J7mv<_@bBG%fF)V;GBSi z=zuHEG!wDmyBpj2Ea9rDR_Z`9Z1>S?{rL(#l~&hs(~?&8{bxf?DF+#Ivc8{_w9P@V z*I*4~mpc;0qgtBu?dFRG7S7AoP_Te#tsOCCfJ1t6gR~duvC;K6BffX*C@6PYx?b*@ zW&$m@oXgg~H*zN0Z&T31((s;z4p626h)WI zdi;u#NbLw|?mkDISdbR=$?Otc{usJLAIHOVPIRRB+{N!B0RGeA-z}TzIC6VglY3!- zF<7ZjE(=K}<$+fgWWNdE*M_eT$lfwz(|w!qPI<5DbwX(r z^g)X9hZ^gfAYz#AC^d8G;oycGKJG0@pdcXY954(_k^)Kk+-oVq$U%jdA7MS8j!y@^ zQ47zx8jI`slEtp}kP(R*D2>X;1&Q|!5#&DQW2)hb_q~^dx97`p^<(p&_4B(TL=%*Q z+*Sz3ws%GLD|J)fJO|c?hC6HkMg}Mdfg`yRmZ*XQ`blSEw;>+m5zYbxYde!L!f8Cv z1T1>@q)hgY;mw=9dkN@x8Oz%Wp)&v}_;?3Ekk1rH=3-g9KTuK#BV}|=_{!uxnkuoL zV0~UUGPK~-Mc;tgKsh~0m$icZ(-O4CE6E~GLNj_M9@n#rYtLv~!j%5NHc2UN#ja_t z(-^S7Ydqq{Ny0jvO)e{EK+aBjtTc(Ldj9ESE_KGYV*?8{pM;B$ zHrYkqx&#Y;Y>m^rmwepTpu$BuTPN)BY^LzRh z@boP{dM0H(_@Qp&L&8x%+?=w_2Yc?u@MeXlI8be;usSA?%RPiiF?`&rbl)mZ;k4Gg zOI?o)xu-+vhH@A;=~xRYiR}KTrLry1V|Is6_+k02rM#hJa%^7yqMXZ1SUVdJ%aQ#I3+sbzfSSK}gH503HI7E!Baki&zr z)emc&N2uEwroTTNAm4mcdk%|Of@aC8`(XdB&v}SM^Yk6FAYzDzvs7FW@`5 za9w5rRw4bV*>Nu|_rCv`Aiah~3}bQ$pE>*_Djn`FWwB^0i60pWqaV7Nhs0BT52}#u zUX=2)c9_Yx6CD&lk7z3(q%P)#r2wY1G>7AEhQqyYTyZ$@YIO-g-|d7Ngsf*Ep37Qd;_a z#9vjKRPDXXVIF+pXzuXV=hlduX@TIf+O(&_;;+qb0^&p!;k&}0O(P<)@}K0&+Wf?_ z?1&#}E6<+QLHBfe)w|l?7)oLwXSW+&(JZ}S=$T1#(SdxIbynbh{%~7n&E+%ii_03M zl)*=I_t3p8CnE@rv7UP3XDIHuqZEk38fRZPiW_3f*w+kIno%i==Q)rhwfh-=z8@(V zoHK|wM74&qLuVnA{`b*63D5EmU0tw9_g<-sN3F9AyjyZ3&C$unjyf#MOG0z}c74K3 z_Xo-R0T7dp)^x}O+@u6c@3ruk`uK6iUVVeccf56rS*G~HmhCx;&<*1x=J0<|t;01B zWa%h_)}22=IG{FC=b!@TZN2v4Sx@dikONW^h~2}m9miF<+X9hqhfjgNTOBTW8%3S6 zguTJ*A0@`ISbZX_;>v^ui=Yx1B6V*z&2`!n+w-Fa{2M?g`83xgNU)0VuOV_kB0BSm zRmQLsWOi!Xo%?Co^Ta4ylo{)lVp`NW=-3`Mf5Y1}8}il^{9OH)o8(7OpN+VC;@*)~ zgQ3%+Vn|B3L1!E^xO{q&<|1Vx2?F%4YRBJiRwi}Hf=H9s*DKO4YsV-h?4d#U%4beW zO2rnA{cWJQEe14~wt%#fQUU^y^O9JGlKNXt+n$`#>S;bpk#jd~zY&ZZuU!$rs($Lc zTNZb(-QtU(ZocP>$~}Lb6a`mcoJ6A26D>SBA<)4gnhsy_T-sSD@!U2!a&czyd!*`o z)2_t_&V53Qqh9p*j0k@jvz2kDif_io{8T~tq}0lg=xSq-pM{0E>0~`zGAkWh6*Kch zez&1>U4Z>w(73ft2i$6Wm+AqvTOw4v!5%xK|H}5yB_Hw_Ju%1DZYs#AJqIf z{@SM<&V(8sVMp%UXkIbLpQ7ua&?kPF`WYGC(zSaPlnn4fc%u=Q6of!h-nD?EY*0pk zVdN7q9y4b^?&bAEadVW8)WYJxx8S2nP341R38)QVGTTz6g@D{GOx&`%p{q+5mBU~c zjs$73S_rpXy$m-X-ia(G_P7E_jGvdZgcE?5!4IjFcu_#8cYXM4-&W!LDIuCmvd$dO ze}8}bLB`2uqT#iC5Vba6I(Q}oNTi){LOreh{rx?xCzX;xHblE$9AKxk=MzXrvB17R zlgI}axQIx0iSGc2EusY?6+R{~krykeg93u1IC~vvy-_md4c|goYi(dOt z-JU<>s&%U|%KXeubGxB+JL*tNI*u#aOgl9U95q?^xNwf!_BXYR^Tlxo4!TbxYC){p zW%%sU93iOO4(0LivhKbPhq8ag0|+8!qU2$p=c`XgK*)Lgr_~2nwNp=lu;FAD0Te(i zqv>LhVa=L}+LntTKPtj^YVT%R5@(wOzWC_bF;mg%`agudWn7e9+r|qbC9Mb|jnXCE zje?3aND4|f4jn@Zf=EfXG)T8YBhn>Er?hl4z%a~Sb3e~pd%y2*fAR~$%(~XK))~k7 zKcK5FgCm(K`1CWTV%2~yv>XG!m$tKntFH5AJWn4S_PKj6u)X~; zA`=Z3_JiHOS`s%O6A);zQX?F6y5#}Uu*!8y({*Q(DEuz-4=~iANar|LPXuIJ_t^T` z2~#@Mij&1$ENy^RLwtq@RKoNCY|5M{tvW`iofFJ53p>n)tz`*V5s&3P55B%UF$4d8 zcU}&{^P2p_`?@@xki}X3t9joSHqAUdpiX4$=@0j~ye$W$4Wkt%G60zT`f8I8Oxr3` z6XP5f2LPp3ziHPO=9g%oED$BK{LBwS&-Z_ z0jz=`)fR~kAY~X5CQDG`hFeuEe5{uW{c|{l`ILgy&HgvEGR(zlGRN;q_XDNCMahI+ z;ETG41Ghg7c!*(>3Z_rTu1krE@e1shO+}`{?jm~z6R$1+tWPOFHPRf?4G?zRDUEBV zbtX@*YbgBJXCp_yJCJZKde5r~AAr&r|D_{9AdKcgd5cMg?2R3jV(T})N=(u@i=6*f zW4RVWu#|2}x$i#|eX#k1^;RP>4Q~nx@Eeb`BE(D4-z_nk5q^1_kX6HB0jgfaY^V4E zEA5rUX-D`=)R5R+15lFrxmlcF+AUO6l}}E@dS5Mzof_bki8c+}2Ke6`pj!a5ujZE5 z?q`{ufZa62rC$13g~xA~I;)L6{-iY8q)msCY{$s*<-W_;zXg+2v9D&Y@!sWuCzP5Bek0Xf1FRy{Cysf>TK`gmhL)Zx3ya09;wQtnbp z5JAEYq9YQ3j$&>G&U61hX@G~u`<0)ur9Ln0aZql~&M^iHr5{lvGN`cA8lC}{m7n-| zsu>2ib5evx+{q*LtIcEg*a-A-)0wjN^rJqGWuY`LMC>M2K1i*C9_QbQ5=tJER<4Sf zsI!YWR<$S~&m7<<#(1ofOj;9pKs(Pm2L!E(Q4wknE0+KvAsc9U(IXoc)HsN>I9xz| z@vjiW0(*Y>KCofmb1^Nqn<}@StLNqiS}EObIK+>_=kzb5TGe6AF`5kvq(hu!nPBrQ zMK^pgeonS-vYqzirLKHOwN zqP8~sg8x~LTJ`-THeEuX(Ig^QJ&zN6ISEfhd|)oq)3l3DxQ^sf50!X6gsf~rH~iS^ zFUd8UZ{za;gDtA&yy*?a_2S=F&t_iK{c43fk2{VLqq+B(It>!i_lOWl2uaJtjpcNF z^6PY?W{osDek$*EgGlEwk1wv^yxeTD9^f+{(2?~!r#W>PD=$3N$u@w}w5G$5hWI@h7u!!SF>=%OnK%!ZR(d;@2OSGjcRM9K%c;=nHOpiMM11m+1)mxrHe{n zzw`fn%FXju8#mx~SgWHNtOj82?~gat!?ez|t~I_2Jd38|raDEO?{(JMO>uD=r`G=*8 zt^+NH1NxnCyaG^EbX``E)$pKB)ZEyXTZCP!TAz@NDsEtW)b~nz!Y-_(CX0v;raUd6sTIYFXfhaBk z2-g4MR-r_JY<}552@FIs#UP#K=YjZInc6P-`N(rOU=CK=**3qK*8-Blq|_T#Rn?32 zB$LO#v%bUz;}*N=3NU{(kqbYy|*F*&wZYzxwR5 zy57ko4Fd^+s2>vG%YsU&%yl0Whqc9G2-@$t^A)c!-3k;M1XeSd1Cn8C;ZEJ<#!Zh2 zmf{h(#5A%%B6%%o(Jps;61h}s6L+13)T3t&p3^i>J3}fw1ivrrmW<1_Z>e$9dCT&j zbQAy+wxJR4%PAwz_c_t-qnD(B@TDed?XiDjBI>t=%idRQzsU~j6GN7BBbW&YGQjVR zrPkV~7lZutq^hO8{Zd?;-{P5^Q;Z_J1spT(_tH@MFq3kgzAIcz<#^ z?=wJh6?fWS0}7($JP=mXKK(=<3t^hy2kDNcL{=Pt9G%3=x>A_+j9>{Wa`#p0S`RpG@&z%LZwGX+lY##f-uoYl_XNbF zXP;$(aP{bLS-}g$N;YeQDffU1K7Ps)^qZ6(U%{9Bc~cJ3#}k7w(rJ=b(g)7>7dYix zL3{*A6JN&rd4Ue!;%mTIW>BUcE^1$=+(^HFQ+>Y%Q0m+nK-9)&^u2PNa5JDi{2psw zGhR|Ojo4i5$NxZz!BVWMB=j2B~(cvn1 z0Z~!tsN;VK_g4U|DmL1<$pH984C3g6R;Oj23YE!YtPreh(d=u_*Wf!c@&9{Y*{@3r z?6)*G=Y1dwp4rRH%;ZlgaC<_HTIq^lTA~^ZD73dKP6s0?{rosDw`l<09j83SVMNYO zAo<825c)g(E1fL23~_6YW@H5RQu0SUk5;goTUypVMe*AINMHWM#Jw#kDaqAijRW@q zsx~03#RY>mKY@(=5G){~oX89PX}~UDB16B{gN2ER9vWsqo0AMLR#fhfGtt)^x z!2T^&PG$PM&gBJ=rTTK|spA6T?0vEodJz$kK526t6gtDb8~g8;FR0E6$a}i_wv*todUio% z$>XWl47}EOB1G5Pj6h2 zM1lhXcirzJ@m~IQfWKaMfKV{NVxw)l{u|x#g*m{POQ64cCcYCSYvvmoZJ&6Lvg)XJ z3ZzF|0NEW3sHa!45-yXp?SlzTRR_DYgsGJnAS!)!5c|8bbL(Mq)-|Vtd(+~Nq7=^M zzh}MGv?&c8WLk;#ap9bWJabXt0Aq9r9enV_kw=)m34_-RAq6ZZ4}W4?PiB)CxNk*+ zitlP~$N`gUG2y?wnf#_9Xr#`8I;GOEznu%zJRk)QxYkd~2lQi}yyr)=PeHs|H#14W zT5~RH%yU z04Db-Ik$nJY=)U3T2TA%_x68z1kHWOjNvIDlv33$n<4~PlVYdv0;q;+p&{O9hVI=d z68@h|D-0T_syBH|Yl{OxBPRFlj-zsxm;}GY0CP|l^p$ZVQSon!pJRKh$lc!^)+Uvn zRO!uE0^Y<~L4c^t0P0P^z731QNs6bZ-4BQ=f;Td*`uWU(UbcL&)c$vaiM(86Ul!P6g z^4)DW%?dDl`H8)yYXK|ixN1!r)h+3LiU$e?#FGIo=4flQ|FMJofwLeQFAIpWz>sOF zmy#Jh7%I2p*c&5+>kgYIW!Eb6Bl!85iuzFj_r2v2_W^ftM*V&Ok#+lOegL3j^B}sV zdBCP#T034Z?Y2jWp7sNL=J)4|oSxEtk%6n5jDXgCyoO;?<762y2|)M2YvJhkYele! z|1oFtRR*HG6{Y=?EC2RYOq|bIoc_2RQ;tEzElL+g74$8@v~)Xr^H-l9tVidKlejls zi;}8H`O<4X?{f|y!MY1-i*c<$_Hdsr`X+YAZ_?<}T=x4bIHR7=uLTGpBib-yBg>y9 z*KOyAC}b_{NZcI2PT#G%(5F5;y8Af3@I~-L^J^OPITHFL3DLdjv^3KMOmSFVye^8W zPO$y@ZYcDDjLfwZ?IGj3G^*U_yE7&d0Z%IIvz;oB1k=Xtpg__P5{j-l|JUJjk8a(s zQDx>=tpa^t^^-ZG%vw@*&BCtkToc1JKhQFKf4u?+0|HhWIlemaT(9pBi}({H&TqEM zfowESFdF7J-+b0hS)=$@#G56G3VAZ{>8wgo8(g^PS*^Dbz#|s2u-u+gb{0znsLn2A zBq`0xH|NgIFc3vgJFnRd@O>Z$6vWlD9rg>vL0?eW8Cl?51Fl(5 z6vcFF3%0P6Be6u2$^&WN??>KEm3C7+*C2j;HV1qU{C%y8!jXVlnA$ zXXrAJNARNtKrdi*PQDW~-8lc-5iQw|Bm~Ilxj*=RvqyZJpb>7``PK>cHg|p`rQ(T^ zV@qZ2a#9?JTk1oT(ih7`M=3rgu#rGaOH|Dui9lt)P8s(X>xwytG?PrGJK%|f#1UB; z!e68vvMp-geAvdr|Bf5(h1`=g<@%DZ9I4}D{M7S3RRvt^m?G48-Qdvonk8U9tKOG& z|mM%kKn~Z;H+#8wM!Y05o&zYzNDEOH+m* zi5K2k(H2!VBh9whn(=9(ggVFTB91sDx}kW?r?CW>rB1YTF!NQoS0UkUSY1j zY_t{Xv+Bm$7c-bD#OZf)X_e~$BqK5_)gTecQ;DNPb`Sn&21+AQ{X1N<5H4AXVfqRG zLHqb}JzDHfNocF2HTFj*sR}l2&Lf-)8K`5TwP7dJ)S-x)|{82fW`9NSxEMyQuQ5&dk47 z24~l8v;oBO-@n#IC$Hzs2b1}%Ct5jy1dPq)>&z7`0T0)x0dRZk9x}GN%pl=SZ@u9} z8!&F#jMev$3fhj{P7`)G?gT@YpLb9Q?5>+^g^!O7v#?mN5qD!(K)Lkz_B-Pwv#dd;2`Tz8vS3mybBZ$Wn||xkDwO|7Scwq34cV{ z7+2aod!4={c(-DhyLv`g^m?D4B#p)W)MfsqQoUSF!K=?c@m+q>cIecZx9$4fiOV-d zNA%p=KM^*7;Wm+^{4LDjhGji+%Eo|XnY>}!*MH6T1m;wa=8^cx&3Yf-W#O7;GpWqe zRtFsHp%opOJ*K<=vA5QLuG4E2DT?)}H`Ga2zvYG-NA5_4JZP&lBv7^dUjKJo?Zb`6 z>Z}vc_0)n4bgr5R6;&yzrn-87_p(WB$rF8q<+z5}CJG-6pof!N)5EGQ1ejbleo{cz zltUMq3}@`=$$g`72-zYO!{0Iboac2X4aJal~8Hg$U^ykj+3$Got+6paR-i!24fgV71JYcxP>5rm!UCw8b{Fq*;rz!swSJKU4 zd@uZOxU=Wi>Y{V9)Y?_`t9AI#y&PVpG6^*jK8OI85vFUO*L&^eHz7}!p%z6TD`4~F zu5D;g+Lwfj zxQxHib^inL-dv7BSM}e8W_~*QR1ODw2WoN=k4UA^)2&gMi&fg@+aErk?=rvWH4QHt zDZUH)&lG^EdR{G+DIx4h4Uxc`h#8$kl>&hVR6F4LJdWrWclo5BL4FBba4cWF|Jv?5 z#4EQ$;>8HW3oN`8L9qpW`O?=P_GJr8h2j_tGom+_n6+WM2-d{a!y!BO3No#A zr`uhr+^_?b6DBHZ+;$!ZxGHGF=;d$VZTP)Oy!m*SqVIE72YB0LYppdZ9gWS>_JV^_ z5WaW*TpUF?L$;aDKnK!?a`%y3P%@h?SH`JL$Dk@+iT|EbrH z_zEEQv^GLgTP(ATdZu|p0F;v7a)8-i!u=t9Y&6nm=Xr#%;cU9k;hi{2r`Qja^_y|! z*bxawaeE^>o4?p2BHI+&2CBgzrwRU@Hw2v8MGP}z@lAnp%d?=2m)2(1v3z)0$YyiE za8f&CfGP%?1ptJPHioFdW?}mdY>?PZ}evf*Ga|}z73EMFWgw%c~vSUfq&R1Xm;BWZt@GredbUUk`l>aktdebyKf7z*Y zJ*|fl>$KMx&Un}IdCCaD_J)PBYyq?Oj$jSZQ-cP%dy1Y_z6M_*{w3g^3^=}C?tJ^* z$K#3RU{O>uU+!!?xVcpYTFs-nhtja#ufOoO0hy?$j6*MP+vkp4rA~kea31ghMVi%X zE}t{oFZTX>vlzaJJ#e;(I2Al_cxJlt^IO=%GtRY;My2#v8sJ@?2^sMAQe=jt)35dq>`yCn122REkd0({!F!Ivzf+o7VfUF?3K{L8s91 z%!Z_#szzi-zAba>IMr*tocb>&_nxVmM2*`B0NXJX%lJ^T5Np50cpTTTLF8Qj4iGu4 ze%(}<>AviCVzLEJOTjOMsL`%_Ir=QXS4*Kc})mcI7G)Qe@BV`JZ`k_fm`>JOQwqD$- zGE+)w#UcDN1Z`hMsvEV;(sRBR{`u)XQKhR5G@dJk4geg4-c*o+68fWjyhSiA_K1!P zp;4&s^Yb$;^~6qtVs5?EhsGgshWBISY(_aWsz#UinbB_|lGPlIM*iW(n9QlZkD)< zdQD7m`cV4Si(6H%(6c(VP^Z-gJZ#KBICU!E~{E;3mD}Y&6Md(NB&hKim|gLR)!3I7gf~ z&uhpgK}VPV&ezK5E=RL4q0)T>znt`|<-NT~gZrOWXR4@#5qO_D=em6jI((w^(w!hlu-Kj<+6D-*yV>5Qc73XUGwF2yBrcHy{lD13GfzOV?sG zoSqUW(b+f!-8;5qKFl+cAH^;?7$VYrp85Ma9}oEr!N|)&AuT_yC7eetp&Yl-K=e5H#V>UV#oIqx#qZhGcIGbF26VYRixs#%6G(qx+34U zW3q?nUWKq_xv?ILV}i+*T%=W-{Saj=;>TuKr!N_p_bpgx@=!Xp)??@f?fLgt5(4_vVQ4I?PH`(^0Q^h|(VsLs2`a2Klql}K7n_9d#a zl@BlL#`>*NEhWDn72jes%C={>{i7~d6Ro!F_&U>eQsn|dPhbb?^2Ya?Whz;4C*R@` z60X6sb?Ha>+_trE79Jsg13ON^xu4ivw<3Kw8E?4BVf3%aV7$rv-H8a3ThhtJ5c*>G z+F3jeJ`orSG>Rd*(riq&cj<4-U{jPmEb>jB*j5Omi$$1Fy1Y@RgyrxN5X6?{_ZvEs zb6CDA7HGm4)2iJQ`jGpoWM*o^dOU}DAapY~ic~W#%DCWNe*b%7yXMT+ca$S|hTqSU zf%`2jNc<#5e%)zA$lUQdB{_Q_7)ANB)MzNGxsdmFT_pDg4;%}tsj3JCI?D09`}Y%g zMLI>xRIROfRnxHWO^P*nqQ+41^I6g@JRng2fRH`)Q&v_3NJ=~}pQ*gZ&s#Uo1uVzc zk^WaU-;c4&*rs%fVj{FKZSql=5yYW;lwLX&uz0V4A@;MAri^wrADQ$13V z<8!RdOtz74V>B})ThhZGv=+VbA?rD_I5m-1QR)42=O3i=fWYO87P5e=zlwI`8+KZh z^DOP43a#XDQdaCskK5Z<7$13W21jHG<8wwbSPu?O0~%?ul9O9L;X##=3mx#>(!C(r z#LuE_6DH>(#%ryIV(%WoV|9Bxkb%6w_NjHe>Hu#D&ZeowSgB&y=7c>)WT4X!9t%d< zZ0^!ZdLBl|wjx1)4812wsr;9JV5`RF4s!&r$+-R{Jt#p*G=j$46yw;Np}6RH{+pW{ zBYFyo?g|Zt9}}yO_VDlE;5&1TXQ;QP$@S*^0Sra`n)tT4`+A3J$xi~OsM-%u=>51e zQKIAn-=Cn}c?q0*?LM#h!QNe3BQK&{+Z&wHlSkX|g>3&6AX4n^uPrvzl`5A&XYJ09 z*b}4d6{5mr(e?Jv9Iwj&wwlWnV&4nu(;G z7g-N(%a+@mQnoH}Mmayt(u>iY5>8C6nfFKe-HoJLRa}C?X_?hBKis<2xIMc9lrfdG z%+HU(7KjO={1vIXpL>wNDN}$D^Qk9UA4vDGm`>{L60CZfzF5XS{x=_sk=LZYn!TTd&(W7t#EbKl;EOkI!OD4*p7eev0>%Qwb>rqn`h08O+NaRqP#<#VO4dYUBNy=sNgDq^VH+^qGmlR zn%Lwf#G9CE#3pc(UXp&@;9XEJblK(Sv;7|CO=*fKzzj*+5Z3x*xIPa*K3>6K)#3t$ z=K{H4ocE7~*Tgfa9^9U;e2Zlwk~39zXOB{!Y@e9m{51r_kw zE82RI)}MNz9r4eLAoM1FF&^Y5w&>%G3|3(b+}Vi0$(5u9U;Onsp~BpD;>|NHG5`a5pS z1Fy4l^7~IP0#ZK_jh;r%xfX)sQG?w=Li3}(-c;TM;>X3wK?*DC{hGg5#I|;|(S2gq zj<$(CW9zd;QpaHOB)WwJpL}~}4z1BIQ|#`h?gBFyl}^m?ByPj*nz&es9_@aRDZB!FlS1%PyX4&f zoEzcsj@h|vhPaz3uKyag)qC3H@BnBmE7C6Bi5re0GFHClBa~NeEbj8bW9^ohQBOX_ zUh<@Z3u+|x!Mb#7r_y3nS7Mba)~x9swodt~RN&J*zLL)2;i!ty#l=jJG}{2_;dd2RAbop7Dd!N~W@7*~JIBCz@Z@j6i7W@5z0#7XjO4*X zVS8(5do86kKf!f7;2R(pxAh~ghU)@*+0OZB3wE0o9>SaZa!T6u{eZ4FHH|&RweQ7~ ziR#+Vv0&>S{@PUt%Pdw1jhLsrEp;~+{f;xWKqcN>RtuzBG#Zd(XEAk=aIH+0+7#GR zs~IjhgIJU+zvi%S99*0NFE4em@gmk^W zw``JY`fH`~7`f{byQ6%9^qyiv=P>~p9R{tz79K9td=rU|(-2I2(>7+gk{;CW9xpA`cKOXV*gF98K=v|jlJg*7P zY~}LmyYIgXU}GdQz9a0O*VnTy3wh7$#LkG84u19TkTpszUptYQe8LnK zMIkQtuhx5A*C~s*@0$&j1kBX>YD?Iz*gvoP_L_lp=hJw-AJK8zMA{is>Iuxn+)6}R~<)uHHv%G zqZdV;4r)z`rJKBejXrq@3hKt=wZ3SFf{MN>uft=fA;PzCU`Ep$;4A!Qy#y0QWYiA}Ep25iZy3iHfLY zo~C=Wz3m+9Pde@BPs$#3-PN<=(0h`riSqBK%x3CO3VUzzbRU=#Mr}{=_PIU%WWKS= zSVmM|j9|u5+$SiALchPVzH;Tp&7K-@VChB=`LwK+ewDFBNcAL|P2GI;el@3Qj6G;7 zR@T51T_pxZar16R>}XR-nNa}^PL>wMvQ^$KIr=1^>dm8*a~0S8__wf~@9b81bdkGa z@}rQUO)#lxBUf8@GeS*(5(e~f;$eE(2KUbsN7e_ARf}_($=l*dtQamge+5h3+sYn8 zrSXPMPT>aMy4oa^pYrz<-S&VCi1z%~eQQWTX>a_hUk-nAV3BMKBUYgQDK9_@CuGH%=P<=mEwrG^br zxo}Jz9QA1N+9YhZHYxlU`vgG@czl~b&nTNQj8)eB=IDY!ru)H(D6dtFwZRp9mJc`t}*dRrlvWkj`p0I407JR_rG|AO+cuI1@bNJH~rqyHVRA_+(N* zS03nM4ci$B?)-}AzADduY8d5m#a?#aZGICPye6=50$XaU{o|wF(QUENhzyOAO@*T38cFu{chrkDXNq07cKa!FnQGk~ToO@N4vdo?2aYd^9>(WXTewul zG*tE~Ag}a)Pn00Hkch)9BEM(KtHBODJYDg;Hqu6Ij>ZIZq|VN4rM@Z0<7bG&Wm4N& z;L@EXK9R64y;;`r$$}6N?<0B+-J>x9B+qZcoaav>t#`WIu;o+aw z7hac5@EL$Kvi~dwAu99V7mf?=kl}eB0TO%vyKA{Xp#Ig8KIpIvA9*Bo86x$$ zx_zaAVfV+qg`a z@OZzA)J9t(3C zcdK}uT=Luel-dMVOs7c(;}g$A)AG40Gu*-jIa`3xZ(; z$~eprL!4&%0-n(=6qQU_rxyAi5jG;+rgTN!4xDU9i+M-1@tV(4cWybMo+C!2M~T?D z7B@z;wl^I_%_}R|Wr8eS_`cZ3%Ihiyqkm3LlciLfy-G+R z8!rZ?_eRlOL9r;hYT6vy(M!@xP+fe-7<~?&@lPpD)CB_Z8wg}Cri(fmI)I4sJ2yrD zQ*xOrFy6pNEA5;7=z{UeZnCs*Z&ZZh=qUo!Xdtwp6GLU(=o*g8QpwE-GX7L1hzaTK z4#7hLul9)D{&)F7#X-uKAT@9ET9dXUblsH*(#%tNTDL94+(1E_GD~Er70#c)rZu^n z-b6vrVY7!~mi^;I()>Iv>dnS#t|J%>8P72@5%+@oUte9EZPt35JlGtbSel9lRhFN) zOz?ZSR++wkHmPy=F>m}?C~9&+#F&SFA~LopAYVo<;e`tz8GC4uYS?8G0**qb}h<%drMFoKEj*`+`pjZT>4NN@j^U28Sn z{?lUfcCUAI$6#)iKxZF#W5l`NUf7Vs*%)neUFjyUoouDF=u3>Fa1^twq}SY`X}iLu zZ8@fHm{=+Z3cO=PDVt^BpbeY~l!T0_Yfi^z%Yy;~SEp{&udXBI>HI7i*7|Vod_VgX zWpwq_2CiBYi5g1k->kKgoKv#%vH#CCO3oiI-!!d$|E=fGjQ1bk!8X?6CD#xAy7em| za&`6opFm~iSF0x-DLBl3V#gww;E^D^qo&X62=qnIz(@fcU;nv@KQduzKp_oKn8$LJ zqQBGKrPDYEExhdI&W~|PNtBlt7tZ~3Yr9hiog*V^4Kk0VH7{k4(cx4guZb$~n-H>& zZar9RdHFJlXT9SiCKk@GzoWS}CmTbJav1jsWf@S?R|>XSU<*Fm8UfGupGq2Dkm}B*VGFcb&3oW#H^^l zS#HV$$FV{!_|l;?sT80FF%nQKIcjzMNc}c5Rq&iZr0TH8ou=mPPIRjXYw z{8zX(tWhfAo2i^`{cx?T4@QR9T{`Bb%ZvM&8R~Dg3gvaERZ+oRb?~gnxsf;E_@)n= zSEFIj^#7ZOJzl?Q%3<(L@;=X-)GU1ihdR7QB&$rWnZSeanOl3_MA?p5J=TsW1F#4y zpr8QGa2~MhrAd!~VEvDvm>%itl2_*A&?f{Ks3}{lce5h1*}MVpcwK6(ry#up2Ok4o zkPUbPp19p|Y$@0e?imI5nzdszZ%!N{Z2F@sy|e{i+nag;Wt+5!Z9)52E>nAjpz@|! z!h>Wt4*e_$EVmtNlxJ8CqvqE}p$xpAB%F|Pwv*W+>%*_ZboYrY`*fP#a(*)!%8Yt* znUT0pm?z)$LSyEIt{^avJ0|eSJB0>7Hu}^Abaz*zr|3jqia|DWQ{AY4gDl&6dBbcR zlxkjN@!gBetP7g67xPOvrr>x1a{FaG{q!YZ%wFt##BZ+A$tU>)Y25IE?BJh;wfFssQ`QJjA`g6j){qgD9Oz^Q7Vfva6|0!L zxsb^$%PTm>*UDV*%*-a51w^N<3wn<{y zP8Cbg%+OzB%t_O6*8h*kfbD`#q5u0DGw8-lN%I7)zr2W_SCYD|6|9@VZnb!;*4v3q zX=KW7HtG%qcbBHJLj>Xu*;Qh_DpyZSA+On1>&-7OW9qOxu<*YEPt=G2fH*R#nHFB? zXFvyqMQckczm2U>=bQDt{#LHGYiF_fGZrq&v*wq19nv@4mEm%pOJuH_bh8-GX(Bi4 zx_c+%`%Mrom4OHK*OxoNSz3p-pMfS*510K>U{JlYcN zp{OaX4h#p2byP`$Rl3Pvg*Q)Vu~I?tT0QozMPJUdSI5TwPju}t{yu`3gb^^opYBsP zf#n-SXPW3{5CdL8U@w%B5hJ`zhd!$aBBOsyo-U3XL_0m@*gi(1ag~{CS&1j(eI~;3 z8un0Z(#|%9n*O-htFTr3tMmI=|9$+jX(%8&a>-Ln3fWw&J*{2;DMWD;CioOF-H*Hn z;`@n*QQDnV<>gX%pta%lSKu>*ZI7Xp0e*6y>qUlCiEt2H26%*4rSG@C6s!5t;sebSf-p%xX|&0XK3zup6+(VwB*R@r*9I zKw-h#kOH$Mk-4{7x-e4VLz4A#&LMsK_h5pL_0Wxgp!K!Ui%ceFuS>9!3#aQ6>=nl< zt`H~HlItL`FKsUVPMO$3&@NR2|BGAPbN3a?Bj*lJ=ypnrHXl%f`~5xG*}YIR&}s>S zfqLhE+_C>e-lU6W8>P!nP3!7=D8J3C#d6$-37>y0*z@M+7C+B^qreLJ+4^uf>M2!3 zQn9ilxA@s&zN^dllQnj#{fED0&uzJCXxk|um7_;z7`Wl-=?>72V3oL^oBC#L(M3zjv!`qgWKc5dIVaRCcF&zuV4 zFcxa{c#pVMsq4k-uagVSo)VdGo_%i7cl5yp+kScvXoK$*o@MS-p$`U1#r=qR5qETN zMgpDf{uAh{V1Xqq4u%)7^AwekKqepQ+#Zwu%ex&GFUsBIsd@9G%L_xcOvVfDG)wE7 zb+QUx;KXRYw;kPj14y&i{)HS9w7rusY3%uHwzhFOY{l$-d>FkMj3nmW-@~pfo6co| z{`1TD22-+pe-UXBB-AXJeE^9|68h_O%gtt9)C!A5#hKB>L`2-LnE-ixf;R+hV?iO7 zM7Kvfzd$xsl~h%qZmqwhU#M?G(G{k5DtjZ`o6GlCx?1B|)w~_sY_wip9d=a8xS(HX z1(W^NlyFyZJ!{IlCJwF>@jSX^V9qhOX04*Y2u>d`c=X zF5KU~`fx4(EpzOC$?m$jL$BonC=fdZ4wpx3$UBy;voa+Q<4;Jc~ zUp|bDe1$0vZTwiiKUs#UU8wrr(f`7k)wo5B5xmRUyzmCx#Wl94P>q*TWtN{?K35)vK|Bq0KU?b}P z75B-i^3FpfRby983ZH7I$8ai&72Kd@83A< z-_ec0n_Mf+?!g)B>9vq~78W2ULb=hIx2ptCAmqIQ7uTCqAuk9C?3BcdMIJHMKfVnk zi8X2URox!%3$mH3zxxsy&mLF(x57wFM9NPR)cz_knGVQWP}>R7#}?kDjtrP%ON*_f z$iq%}t&@q5F#>+T3Nbt!k-6u3w(+4C`GLSv$U)pYCF^y}UQy@QLc@qC?L2d_S+^@5 zT2XjBK4pGdEv8pF$>VW^7~e-ilAEw+=6Kums`l2u-NAu0y@|QINw%w3n|LAdPJq(YV?#}sxdADUIf(QjwqsrKR-Rd0B zQ`HKuPAIbOgRBX8Q($vIbB4|XsI}{Jn2BfvB1}p?r&fLb6wfsfOh{@6S`)8_+klUb zZt9D~5*6%EPz`9FUD5{rRVDF3amz+J%bH<9I*UaAIJonL4}6`-Qg^%uGzE_lJUGrkKFFk zi=AWLY8?HhGjt)U+yN@WPO1D|3DuUbhBi0Xb%H@v|9Kly_>&)MA#E;5!UKnjhC~C! zs&@W0MPO(2?`V{u*)yqq#Mw@C4d#<%(ucDV@TH~(DJO+;)J)Beivd%eYMY6c!kXWY zb&zUt%~mmpPF~3_#16E@=9k?oeAubNG#FN0Tim5dCw4LcW!xjvU#fJYj4Fzbn0K1! zifd5#p=MBWOWKsW(X9OX=!1_+*Lg}0 zO5+z`wr-Q(Ui717HgW0A_1D*SAZhM6#wU3CjzMmL?)ndHVTL;Py)`L_+JU6oM}OiN zeNk4VAlbzXL$%-3md`vf^j$%KV-tiJgnxX!hD5(a;P>B0S${O!)yO0;yskJ3YEjl9 zqpTvi`)wYVTBJTN?|GcFIjY%f-{@nnciyi+*B;^Bw8wq$^dE)hefG6>uc%O%kvu`d>Mg=`9xf?pG_}T-I&VvG0SCtoPiMzOt zZMHgEiD#mVEk41;HovRm#ohQFqg^`NinUmoJ>Z&+ffzI{y`(;iOFx)MDtH5~k;@2Q zHFnKwSs+6`8pNy>d8)Y2YILYVCGEwSubLLMEn+uf7bSQw{n3Qvp~!3aU`nH_1Uem( zY$W=l|3a@Y&oNH8c^cj?RR|kO>P2F0W*v*OCzQ;c_$6mpZ0UYDNSgK5uIo)KJQVkpw7>-r#PER97bfMtM{-mBxw%exfXtOuvao?6 z`EJ;u;u|ln<8O7wPoQ8el?0`7c4HH9V-b4a&yk4dG=W*d4&Nm~F@k1qdNeeV*Gc6* z$C^35NsgkfxJNk&oQ!5(%O)-T=-fT8y?sCZP0vJ~XueujkU=fm$UAyLr#De>C2xja zsNy7iTPN}<0*uS4WoAyI3vX9@B2IS*cDgo0&N+1j-@>Ayzv$N_%kec3etvs4<7`Un zZXEg12Nw^labYsP-?0v|m|xm*Xt79~?HL-2^`vU&DO=L1_oj;pT_QY$E>e>3g7ixG z!SyMPP=*yXc(*^H_9P&8NL0T$=tc2P%j%TcX~H-ritQ~p6Aw>>X~u{?@n~l9hFzF6 zK8i8%Q8Ve@`gtu+|Mvg17zO1=!D+Q z+=Qd-i7;IhzcMv?jsLe;@599{lUeQB`rzc+=YtFny}J92`zhD1%pL61qN3`0`)3ok zg&jJ-pmw!Ru3>lu_?8K#8l6rpU&{~Al<^=Y_m@5rySnWKuc{Hr|BK>bt zirC?!o9BCUl1~BxZzIzY1`v8CIxNg0YSCYb(ING{BTE%oLQ{`&WY~%%vO2@amLc?} zq*!jI>-`0iW(+oC2W~a@Rmfry;aGzd@{gq`ZcWV+AHvoTyG%rlqbFDDV`WBcpsf+t zFcN`;L-=~~80$?%z1%0kJaq+W6mP;6$Nwnkbj<%pnLyq*Abo1pcj~?BP70?7bzc52 z+_@)6pF#T*MEmEgzF*G?iV|HMX50K_{J(pF(K%4kNKWL^mv@iisRaQ@aC%LUsY;ZI zkLp=!y_U3y@|vGKGb3o=Iffk(Qfcysef#+58FaCEOW#u=(WGfI3p5Rf&%m1rk%ra* zCy$R>fw!nU)6xvt*I#ys0>dtPAUzJnmeJf66{jd*RM-{Wya5rgt4v%4BfL; zcU#XNic#reMQx1eilBbji~LNb#eqDVtZRXE#o=Q9^6QTm$3Z6FU6S8lbz-4#UvR!) z;$EOqoV(>{U4QR3_y4(DFh)(z(mej0V&CT~6}#eqP=mHa-`J$SP27iVL0ei2pLbS6 zH&3cPTysEMaO@)qJyT}?@;bPhazVvBF8C!>{5=x3aRchMZ(;5??1dV?&^;Y|xqXFC zRs)HtUE)Q0e3UcOovaO%t7^>K{`XFq#=WEAQ4C1Q#X1Z#)u^wZpm{?bKdetMlek6`ninpKy zG(Unl;H+xGpq7od4|Hu>J${dRfkwl2+%;c3Qp);t@P6tZwj9tE{;vTmqjbQ$huvae z_4;6ELwGGSLP!n1J%)!Iwp`&#exGY6#OuytV5gm^GC6WEKCAz-kJRo zf=XeVxnOigpT1W}->h?^JHU`j>hgbX2iXKfK8K#V+eh*7S|~5Y?6$ivyVH^#8z{TR zayg_Eu1QlQ?QKdWa5>m%tlOSz_w^^H*6zqjs4cwpA}QcrlB*wfOi!XSx!`==u!+5B z;BoeDwBo!DaVll|+l&;h1xuy<4gIAzy!WjhzZuEO`~Oh()?ra^YyYrFsVE@=N)4eR zjX}fEpmZrBF)GsCAPk6zAV?`7(%qesBZ5-G&^a_icMUMWyleLU?Q`}%&v~BfdjHew z(uwa{v(|lo>Sok?H2UP{m>^qNtDGjB&yB2XY>Pp1r*` zi#s%-QPug0tjlxA9)yvRar?m#9~l0XwgEt|1J(;u^r&Wl1ZPc?+6z{b!N{HTumO^3 z%bo6h-yNMT3pSqtM1(7`7E^78jeR527OC^)4zfB|jNZ#7U95;k^riQTt{#*7#%1j! zk+InW15o#~^XKFf--OpV&Ga5U&YMqF3V-h;*@u$OVPAwE(@RZ$B_%0gs==38%Ot`A zEN?7)GH@~v8W6tK*W2M4J6gy&9Z`%<)@5Xklto0LQ^Gb1*ygwE1^8F)zk1jdaPYjZihl?~yjV7Gbml(q)qb@)tKM2HwJ5}%#g}@GQ|FUh;`;&Ly~}Y8ulXrxGdd$a z9Dj`cVH*LG*xU#^3`#D9Y9Ghexk*)b#foy{Ar|&M)`5C&Gfr3i9JO%2`MNU}M3I$_ z%CZ#AJ~Q+y`Ycif@k!x|5*Lt(h9=g%r?nB2l??ot{ZYS+vo*e>Ri~Ku_H&`PiB6KK zsi{;NChPYAjdkV;Bx+zYTn>I*R`!|L)#PH5V6vAY3y?S#M88V)Ua}qru@#4hn#oXj zPF&@c%5~8oKqDzQBbL5TOOFOWw)pYxqJ(A+an<8o?XPZ|LLd2rNlK%!lzY32bvk*v z?IPhmt3xyvoiR@g^=e(*V$g?}Usw3;q?}%<+3BT7D?a;HLckcpOw-gZY zTuSJfhj!Q4OMNyQENu193Qwa`s{l5&ctA4(aup<;t;b4!zxnmoYt|rU00M>UC4r$PUhqMCj(h( z3~C=(E*t}_?GHleZv`ABWU2EMG~wD+2{o2c#y+SIWWrjhvzeBoVbWo1dT3}`;cecr zAGVRVNnOpO_}@>Egk`Ggm-QcfH#kwSZ>hKy#iMYE{()VXoz+};~Hw-e#?Kx*d@G=DUc3%ybjB@qwwomQw>F|Az& z8oB)$nYYGITwxD1CcNa-#xWTH@#&o`Q8J{{k!3!UTlZ2*j>%RVcRShb0Y_}3U<8(i z*H&Sp^?b(Wis-BJt{YOpRmZU5r^VBRp$Sz{hARV^;Bf8%OohTzXMFzU-cm37%0xDW zpzW|6M&jd@2<%Xm;4+YEg?i-4^NtJw-3JjThQMiAE`gnxf^DBlKbcKIoAzul4?X9N zv5GqT%+Z{qU+(1n5#(5K;j(6zJTtmE_3tr+9QooBw;t7mx8YU>cgro5_I!#AmzTc# zk;gefSbkCvNddl#SbAlSu{5?gP)XtSiN|$Jye9e#uqRQ&$$TKUBLxI3S~UuroKLzx z6joHht4Z6fmh*euA=ccH59R$)hhA~A@o0pmtZ-R2|4H$ajq=44iPyL@NzhF~DxA<< zWv&Hk4B>{sWiS_@Vruz7O|_}GUgo)LW;NB=kR?w^1phCXR}jS>8p^g|C2Z40bxgT9 z@&q6sc*IbS&Q~Y`dv2B?Wbwth=WQ)Vc+3*5^2}K|TI@8EbZ(SC}gyZ+_a{^#Yer z*BB=4w|;ql&!b(-A17DD=&M#_N1f(p622c}Ti?-mseew_v8@G@r>-@H^H+mpjGN=n zTtzD158*2jnM>TiZJI9A7p}|d3W!|v8%)IrsGko0w0^KI2G`>_0*F9_t(v(Qus1A7 zPi-P_>Y?<)nIFi66qm)tuEwE!4{V5RCsDyeMYigTNX(#3Ix%gBq;r<=Vlf1?*;(p^ z&73YQyR4)8H`WW~%=0Zx&aDgN!`C5`2 zO0Fc2(pPQBmYX4mycJXJfb?~sz$pAFf)w2QFowT4yT1WZvxM*(--CA2xGEQMF!4I# z$uV(%mdO`R_p=`lOn&ki6Y0S=*gFRMz3BN{@QeanI>qE}LsYIdLmRveV@m*GKXy>% z7N<)@k%BqC3&ilqq}DKhTh$g5|*$Z!!UQ02SmhscYes9mxPM~b$?>|zSQF?n^D>Q_{wnC?(KKC zF>{yLrl%0eIiL5E;^;hvoA50tnL^DB3<#gbp2 zZjtSLiX%*pUlFqGj6Csx>g$j9^=B)mYeWHMwwBtWSjDEznpwyP6kVgxf8i}!NJ*Sv zp73d)IyR`GcU=*F3obluKzfL>NtU6e9Ol^;+XCN7xoqE9Y*9LWbGJMlG|(IvkRBof z{1h_}O+Y=a-zS$dY(HttfpJf)mD6{g&kBPpEgciYl5`*Kv4dNJwD&AN95%B%v^Wwy z<*6y_i;F$4FYLKZ>*SED(OtRvsa(a@Nw=|W$QBjHjvb7Wd;6SAI_`N^h{?pS1PX@8 zuQ{y^OHZpW4u>aHecb&`n2{i3wEn)(qIo6+MZ0{1zIwfBp9xEzO-*&5K;YqfF#$mI zH4fh$Cq-T!nECovU(zDPRUGt{o%@m`;d9VlW-^aF_+gQFn{DYihiU?-VIc80j8X>8 znEQfK63x5UzgJ}H?rWT-bE;H185JIPS^Na?7qm#S@D0Lmje7Zw4UnFRl9H0*&Ibmnp2>)7xOOtqIrnIjzrjG~juM zSRF7bYMnA2{$=~Eak1xOhq*uEaP*C!_YbUHn!yqsMq;Q^Mw0ey3eZWzCIoO4E~k}6 z!i;6M{5!x#YPuhdR(0@uYeMc5ZS%;(8PGRU`9{K}N%lvl?_1NT*hw(p$!FKtrXb`s z3kHu>L8a34#`0`oUo-HcF$zqvS>9PPOht8@L7aw*lV#NF7d^l4EAioeBxh<)c>!Z; zEpA~osoV@E4^guqI8PE)^=(5viM^&#KhXH(#+7}qx0^bJuhnXN+TI;`^B4-7k*AU) zI|sewYIuw4fb7RG9C7imCfz4}N0jfxBNUH^o~Zsbzp8%~u<7;TjxUwB>%a3hUYP5&QU%53$wG(0nKMR!w~6D>z8@hah4|SCOJP1T&6r%qd|N$b{TP%-ik_yol%8mU5lA9xKfx{mSRi z6^Gfbtximt8~#zu;QxlOwHw%QI(OM-8UoeQhKw34<{xebX_$`Px^pK8kYT-Rk9}%Q zeiDJ=I>%|y3Sbw-%76|ytFmeU_ddy4oV)xyq6%H*op>(kX=-?>-5ck8%& z`0kZ!E?2)dG3tn8rxUcA2vtNHK5`=$^c*PO9;df4M3}z z&-#}R=kKr$AgG2RjnZJQ;#`z?kfNN?tD0~jFcpe*__nQRFa+jQx>Zp4nE|*(2=V;_ zLgd#SC*Ss}peS)_ky_f9lv?Gqf{dK-U%x9{6ozUL`L85=RS16)E4nyO=?j zW>o4H=&Gg{CN#-#9E2YEv`#SpY$_3fvY=_h%&;qJR{NQFyphSrX}qwr^n7RET&>)B z-#QwC?Dk_E!s8{eg>U?x75CoHjcXti1SswBgCEm(NYt$d3grC!{HQjsH@_8pNX{rC zU1`YBlUrA+^60&JQ3jf-5onhF2UXre8cQBl!BEw`@9G-#t?)5|b1>)e7j;GXhP3Wf zb#|+sGHQh41G_0I9Zu(}1i+79RG;ckMGAy<1D-x3KTNUN&*3v?l<`xcoD#r#EJ-7Tgj$nf#4V}Fc-(H{|UdYyDt83x$o+2yIHJUWtr{HCiPtN{n4f6QvB-91yR zNK5uM0t}7iOJaYVCtfn3L{!k^hW;@TbQ*G{bF5r3KIW9hhzV(6XKUR`X0I0=Fe2Qk^W6lp4m8G=LbRK32P-uR5osTS9 zYzd_^bYGcd=#GvTwRWQyGL0#aJx~O=++=C`)_w)qB`)RPHltLh8xsdm@2c0UqFl_ zcH|W+-Q-Mxlp?aTux&N3Ns{}e!)s3WtlaEMz`J(>VB~Z5Gj+ZJ`}qg{$iTY_(by%W z)rQ=+`|7~alFdm)Bm?;`7sT%yZD&o?3z0x`-~E+r*>`WnzW%#$80tvG^!<?MmL{!fxD2$-(e}BZ(aw7AX#IOkXSlq_iv6aI z`UDoz1;|-Xc$s#7ep6A&*sr$3z8OEpJ#bS;GHZP)~ zL2|G_|8r?Y1pq*?R?0*&JwOioKLi@iq*|t#+`4ENanPUV=Be>^;1Lq0X=>)L#ihvM z^JJ4RSW@AesrBCl=6^$BW4q_s&k`nIKS$5JQ=sSp@F(je1|7Bhv?!D}m#8pFzFb7nG~w@xsW}=*=NfWF_qod4p=OJS$Ha{8Tmd=?g!6X|kcoW#7sdO;|@K`T9ZB*_l^@+4#GU2wy#Vv4Nyt zq0U(lU&ansU=zriX=bt*5g@&EWu3+}`Q5KgM0n~@Vr_qEKEkqbbM`!K8w8N${B6(j zjj6#DC!sF=I@nR&kz*H=Ob~g-%2yH3U?+;R9L_65GtU3z2w=G$E=QNNJ=+j8CgpP~ z%6}N*dWo`71pbpxojRj3ndQQdFV8PI;Rf^XR(N}whq)|Zt2%JeNyJz zeN!@37?egiQmK-iq!K79gx9Flo_+gJOF^#!ENtmo_hYOpsEKU<7c`fs>03^&@QEz5 zCO~Rk=68xo_JNKHMrP7^n(WK`h?$v2-wHQ{JB8rgyFfysA?lo!4)HlmYQ%1cgVftw zUGaKW7zT@BpGeP1 z104$rH|8l=%j^o@t-NI*3GzzjLQTYoC<|BG~p6)KYH{b6Om{^p>It-Mn4S3oI9_{FYuyi_pk zF8XY!uu#+rlIFGclp|&!a$Nekl;^#V=`({l-fdW5^Dn)u0o;Yryz%}DUSk#QH3%`+ z;Qs#X<{I9#y~t(=;f0Nj%%>i7Tu~qJl8O80KiyW7m3u$3T}sDm)mC$+g#+_NwtZq^ zJUM|-?dYg79WZ|mc_|0$+&Z-`oQL}Zxvn1H2}F-WuC*787dxR*x+TwV+l60~ir8F1 ziex!K79V)I!6zZZ`ss>3PA)t@EQ1Gh6%LPB#C*S>GidxZ`?LI0xighr`0j;^%k6Nu zHTaR^T}=O#Yo~-fml-+k64&h2MlbdJOcoqJ2VjHfb>!1o_SSk(Tu1TADL$(h+#`DJ z-3d4J-D-CKWDTQy=g|!2y!K^`@zk)QS&u8n zV_*s7{%!A)b52seXCHYQL9)B@ zPD%FqHJXbCLJFeo!_h2YK;-*dvnK603QPY0k$3*!^L_0A~-Hw3eT_IYKl7ldhg zbAD`={v{V?bAmx0P|$M({u>j8hbJt%*=o+{U2aVlYDsUAcg56%*F=2sbRQiV0z6HT zl-y-n|KbXA!vJ^+1YG}dAYM#HoE?XN+%X#Vo+tSf&WeA@aJOYt(PuAA$GbnfdpOp^ z&6#!RihIG6x*b>95e`7f{ttE;1)~6=;T^vrze)j1`EF30zDKjO1sQYP5#pV4{RCij zl`~;uC;0TblqINRuQ}Y8*bj#W@=2tx%T(Xl>qVTop~_w)`ahlGaLlz z05Pg_9PpNEt~ByQ_xL$$y*dSoAVc3h3-cIk8>sPg zxQ(Wcoj^I(R#3ELNMUSThr8A)BuMkDsy655V+~&o3{7dxg38Dm{JP zXrSm{0@QbhELl#7&9>ZEmaD%*+TEB0-tWxwt4iHeQ@+)q%Z766?#dqN?rQSzQOt!kK>2@OEqsQux(jVd&gL?E# z;UL2Z5P5flWt7fHw!52!?w-v0ol9J*p+Eg>EOgPg>r%GAHQ$2>~N?$+y!Q-z&2~T z>wl3?q^oI-5>wQ$g`e=VujzJ~AUMoBs=7i16N_?k0ndZe~ zoK9%ohhXYf`YG^=B)DR8HB0*>O5V&V#$drn-NkFN00Eh`eiyYVWkr$+(sFL|PNs>g ztIEv#Ox(6zKCE1f12qNZY%n;+i;Qgbwb{=D6VfL!r+C1le7Cf-LtU5NoSIXade|L8 z5xKtbq(gd$J&xIRgoJ=uf5U{;h^HjK3bUO{V_g$&o3AI_KM1D%7;yqYiGG3o#LA13 z_1|A7L6;vTT^fmP4iw))lI*L+$E2T~+Fst;Dbs2^tQ3yG>X&6?ky1dr%>-!w<)r(I zBuU=#Lj`{G1w#Q^>;-=PF!PmbU z3oy~*Y~G2YankkM{9~$L%gwUEJU?fv)gmZ{5X~k_jQYHG%9+MFQ+mf`9 z`aT{@P&&z9bX!}2yfR%>b?dgfc5LF2mmK@{Advs`N9*9&UzOBZT+YnF|$pSQht_n_z7!JRWa**_OO%C zu{imvdGq@i!*H3)JR>2su^p!YWDKATsdZ_O=6AJqfxmn+?Tcf`X1Lt@1^e{QQ(!d# zF(QAv&7@|)VPW@|h?o_6_{<5BjCr8^nNM;sZ#W9{^@YtqkKElQ^=kI~7?n$i(|m_Y z;&JH5KE$Q86_u#M7VOJ&=N1=%rzaaDGmpz_V2u(~vZEI;t6DgdhHXG}lj0wq>SW04 zTlG~1Zq#q#eke0(lQPv@6>K0cqLMEPzvwusM@d9*U1vj1StH3XFjJ_-rP2z-tsF17 zEOxV~^OifA>LeBfRzO{HsL61V?AB#bN*NMk^HHTwDr9`lfS+KlwQlQ7 z>LlXbE-Kyr#0Cnuj)#5(7xw8lCK!IV`W(B63>F%^?O%NEFxwG*h5~0Vu7gGcdOHnM z3jN;s1&ZP)0pagl+F$q{A1&SlF1eR~dsd&WqtE6aQAZ=yHPU%*$3JayZfR;_Rs17R zCk`HaU$4lJss>ksH`l#8oVEr^gylz{`3Obps#9p0u-D(59Fhq^GQm&w4v-NKn6$mS zbGq7ZvL({-l|u?*t<+=NkswIg^|Udh`UQc}p5L6(q=o`ue?lp>53X?=`NdUk(x6ch zd4O|>#Kt1F1(4T*3?WR1qkxSJs!I5lRbvG7Ew{mAB)qWdb6Oy}3BBn7E^1DlEZxg# zi&~@?8=w1$hq$c~dK%|Hp^BM|m~vgYHa85SKBiCh4smm>&EIT6x;||IaA}KHBcr*Q zKrB{9M1*m2H1=@xMFat-qr=J7TV>jxZ=2#>wJ7FAK`%E+bf>`~zOcf9dgFmjteiaj zDyVi_R!Q(yF?_LmdRA8r%yx(8|6Lt?X}OJo5p}0Kve#RzjLbX$Q!UHC=eyJ8Y1e22 z-+Fcx?*puW`EBgw%ur{=9;s9|j396Zf|JP~gdap+ja?T){a>dwOmUOtpCR6w8ajQsw$Lph;cr^Fy5O?q2P%N zftDN=fqR^bnWxX7SYKSsv(;hSaKFC7V%(V$Kx~@Mx8K7tRvuU^pQlqBv z{idUd3g|a)hOF}FYnR>$bWwVDJky*g^3upQd-siM#(!;TV?w63 z>LJYJMdTN!1yvO|_DQy|J+$K#U*>%;*1i?am&d#wNM4zZs_A!31_W^mHAihfT* z^ql48=`n3>mG8;jU}U+=vW++N+Y=tzHK0NEIdQyG?T3N@B~5Xu>en@8_~G~Wck#B1 zKTP5PjssRqm6xBfo6WSn$kv6P^7Mt~?M%70#@Er;+fVmD*IFLD*r>m-l}TY?r5dri`DAnE)A7(}NI3biut>Z0WiPfVl_>3C!{;7L5e!6-X^ z{s;C_?Jmcl-9X&#JUc(M@9>?Z4|1H`$op5w-WW*rfv1tnB3dK16AU1W+58wsJ|O(l z>u$KSF5wwCPH2b`nR2c09)4t$2z`23?Tpik8;6n>^#ak$v+~W43vM!$?_vQu0AbNM z1!GGx7LiK*>*M}lDVlgrS&LYAD-UEgj)sd{OO})#fR;0CrnYUJay#7cbV&ulY^xQ% ze(brU6&@va{ietE%Lh1{@8i`or#V!Ikxiay#Xt$(12R9CfMQI3nZbfdxE{A1cWS~w z!n833`7s=99p;_*ttuSuQy~1G_t+yFrzysoddq8~LnWHfeg%FE2DzR-8WckAJvfRqyE?$>l~M#c|5cJ zcDQz|no(Kk_%|UtIbh^t<4^ut|CG;Zdd_fQHx9^-Gm%jNKx?PQKo08}O!hp1cxu2D z0ja4SHtcU!G$tn*sG5R0x}+W02u#}n_E+Yi2OyZ`_qg?)ML!cZ1xjsVQ)INBXtxlk zYkyC<#9Gw~-NrF!=^S{IXUyeVSgI%$1&L4*&2-)cIUqOr{zu=0ziFnt|NMr;_fXcq zdGcnS>U{&;v+7o^f4cU>nF1>pA3}Ewz>IrSd=#%b4v~WQ^O0@~vG(3mj1XqQ!+C!>$ zz6bbBaVZs_DAMrQday`a*U?_DUs{w*L>aiv0vy(sNQM%hAH@mj=?ocKm^Cx5;-ODD4jbuNcTuyMi+cH;F12X-wi2;_%Kjd%3GOdtyZ`? z^n8s+S*K=}I5*nbgQ-f;sX*0y_{#8_+{0MVtpKVJ)1xD-ZU#{3Jk!8 z+6G?4rU9^p{%wHfP#02NQf-JA?eTpP@}QdR1HNzvXq(^n@#5Sk4OvmFI<#SL0NHwjk+2XBs_eg9i~rd+f1n2GZ{T|Zcl!Mwe|AQpWfw}oM;Vs=(>(hh zK#tF>{CuM)IJAMM|KlH<%NyUf{GXrsxgvgPSR3(=5*YOVUtYz(s%#Oe8heoL1r|?$ z9enk-lvCg@v;Ujl}%Z&>>$x9%>cFAu{S($OFs4%`*p;J^P9 zefsYoI)2J$H>*35x2?OVL^e|6rHM`u{^I+iqy4|06L>Hz7q&y&;I>H;H`E2Ku4RGv z)jogFMSRH4=IHu5m-YYSC0H=FHo-k03O}v>%w>Cf8^oynw{0iC5s!azGL*kB;CEb$ zFdL>4^nk+u*H-!Kv4gvJW8x#YCuArfVb|CI(xmj5m+a@mjqn4; zAU(;_BT#H_@B6hb_`7%DG2{2NugjHgU)b$eMyHse&(o67|IJ zi|x+)FJRRvKZ5`CZv;)sajU~uXy1Na-gdkqt*1xx7>wRnuAcHq2PwC`5l#L%j=Ufz%R~SYWjOcX-5UOOtZ)!9a;0gCyYNW`(h( z_@N#k;$DEh=hxTCq?l`xA1?lJKA64xHhW_?~to+LI|Ma0EH9NRmhpnp7z8E3Cn5vQtrWsnsRbXcg!3$TTBGd23&Z3SZx zLUIut2jD#W5Jf!=5$Jcgmq%U@kvR^!Gb46Vsge*Cb}c=lT|1Us6r zVGYEHf7@*rljFx*BR;D=2BecKzTfskfxyg*O!_^r^6=Q5ncpvu`E969-OVBw+@fPE zsAd673O?%q80kP#e;sxS62J)1S$mr4m3~x~dHi$29{3(K* z+PNEw&uoADRbr75g*xy{^{3gOdJ~`_H#+%hHE7>~*{{eP7aV^laS{m35o!U!F=>D% zx2$^f8-FhSEpdVW)LbY1*%Ozwk<$^5RA2|WPo)0hA=~lcF#rwer?T3u-zjfah@&yS9 z_cN70$0&9^Wj3v=0bA$coi!=!9}ykcvB^w=fU`rWa{N9iQfG*MFCTc-nqog>!0D`)BPL3H{}!qz_tS7hn{B?u|c;`qv5DPJuF4XE``Vw?bERjMkz5 zxfcMO@zE@JC<=%^M>IF2j-)|6t17o!au&cpdV&4|lp59(2PLhW?fiQL>sP!UriPzo zcC{Awr4_c;Fqsi99e-G|wjT+vura6P)jkFpooqnNe_NS>N1zeZ-p_!e3dp#>5>I5M zf4MWgz-=U+!7kJ7y%*s3ArW{&f}Fhl8yn974~Q&*69R}&qk#nMi0n%WND#bXLvgwd zTY*|I;-r@FS-;&X}jpn^{-Rw){hW;jej7*5JBk&dp@ z;Kb}-gz_b69G|v;IOc!*Qha8oe|{L{*%WtQkp_HQDjvGdJOkq7cJn<8r^-Tk3`VsF zB`hSpv55Tol`FbUsVgzRC%%98a+TDW_=kc{y4xXrN4XCtZAhGOQ#}DLUW+0-uzPRR zd6=bzt3qeQT(R*wyC7WugZ>`Zb0Okl#yo2b^tZrIiZCzB{yV01bi{m24=FI}85EIy z=T521-e45scUP5mpi)c;${@{5aEW673;XdUW6^g$;$qDy5FJJQjx}o@8ceOQlsRW> ze9eNkAhssF<4Ybrd(GwoO1qqb^|eqpCfg)C$*OUYsEP677i@HnKGs+_$KwY5Jx3pp zq>Z3;FWHUqJ^T6I&`Z}iQ$J%VZTt1sGL)ZG)%$MWqltDyx3?FH0>MZ8xb&=`?bK&O zhU!${Wp)~WnaS-i`FbEZh|-X}{Ne5uwp}qgp_4nd=ge z_iC~44U)s&?*|Wdpb<2MGUz|{<3Nxp24GFqpUfxAFRyjLngT1;1_dRYhSQ&9A8om-= z5s{}`z3BF>cvaB0laO$Ul<>l5THCBkkFCAeRBDQ?0oLu+%)A^H*d)qrz=3Y$Yxbvl zNGp4#)_~-fyp$+5-&9-)S z5S1|6TNbtE)GK2pB>FL&ZOiZunszmA#maQdiy1m7xwg=w|@9$e~NZVDRmyzFVP#epBoCB4SR~~bIP0qWs_}-T( z?^?E8<7wJu+E_MxRUyDIgcMUH81L?@VIThemRkI6?lYRzScMJY)tu2lO386}c#of) zyWo`b+vi~=D1My}uPKt{?YhMACX!17A&rUOo>QB4evQxKpK9Mx2c8a(qmZZ+`Y=~Z zuW4Rd8{p7PD;Raw>f}q}xyss?7ywg-2`yXO#Tlc=LHtZd1n2!O{&cnc$_`O(fJAq-%9{7v8JA@2`At~Sr^t_nQkfpj6|<( z>*=Sv&a|L|W}xADrVJoOLK0hUz4B}|CH~z4+25bqby5T6sJ_=>*Gy3oNNeVejy+cc|R!)SYU+Px65F9&By|NQ-3=}tg7$01vwyx;Q82>2z zXOR!vT>=g@HX7MnA^O8M!u?KXP(OglV z$-7pSe2KfzG7&MAydIk8a7wU0k*448)ttlo&~L`~md5UvPdja?l~q=SM4~o_O0&%% zvU_VVDm-?(r-}ASp84GFe#+VrarZtxho+h}Iu!4fDtT;P)c*w=6rr@jC_l|6i`hG^ z=4r?uuXAv*-SV&I*#H4LI)L!D^!k2f;_fiBgc3eue@2Ja@uq%_NO2X|-~qL+`q)~;>6oGt ziccuIdI}1S_umrki1UWBK@5JeccMK z`p*tq6`G*0T4=2|_+fiw%VX*lNX;)BDdfV)=~3K5#)Q4n&pLN{gUXZQ2Dxas5ZU{x zdlA^!$COZm=j2L*?8L}*rnx(hgI`HVzY)4_bEjaf|JPs#%LK9|>B=47ZdDgclf#$a zgHTe{b|Tpmo^%q)*fG%t(#(fRQRK+Y)?VynqLJt#E?NyjDv-n&E32?;I_G!3?X<4$ zm(DMjT#ILjUnE+`FRb5doiTp(d_y2*UO9OU4>G+S1qB+&G74t^M_3ajNN7U((&Ue6 z=7U3KK!~wM9%P*?Sd8xnb^|X(P)%a?hNiu#6efnLy|R>a&~7BoX`x#qlluvJfC-r8 z#h6b=&xyaa(^@DPwVWQQQI^6fFs`z>?$dYmHn~PMGOh~ZO<3F0=MTPCj)j-KLMl+x z+4b!cX7P^8;OEnH!Y^M1a}vL@dout_%@qUpLBA*&PqJ&Qh>}1OY%9JPk(B{(|7o;q zmzcyBu_O7#@N1&!V44OFY=>#OgCGedwQQ0?v0b=Pww5(;_1&T91BV#6vL6on53l$H z<+Ro^T3t%H-vJM;KLmaNb`aio)c9+c#h_b4;{G{gMCLf*9hEA^2Tm(jjik;U9euv7 z0&>9pF9Thea$N$??*8T~fWJHGLK=S=59p^nMF>>Up zlA6_Hp*DAjj&6;w+q#2TRf-h4Gx7u0pD}rPFsh*A+H5_REU*$>*_7L@be@h@32ys& zju~(rG^5YM9Z9vNUURQ6ZG%0la(a8do3 zv}^63K1~%EOWaR|pIYhGyn-5sNUxKoO%B!;sBb`$HXl8TLY{R$$;`2qV_;$~iUHr2 zjBu`g@Kg<$*g=nYWq}Lh4gfg7&>Y+g2j}{R zNHmn>!ro>;o0IS93|Un1b1hJ;bRw@xKor#tIi1`R5v=zoVeK{b?enj^0@dZoHJ}$^2YNwT%f)XD=6E zN?h!4)c+`4hSoo)9&^jm!GMnT6g)v~c(jIBN0KO$pksmRZeT@*pov(|kJQ3Do_&zC zHh9KHuT&NwS%OpjY!gJ$>fyhtDm=cC7BY?dDY_J-f5t}O3atz@2m6SZePw29_6fSv zYwoW!qt7;ONa}A0I~KH96Um#kR&2l?oZI33^OybH&IxC=WNY;larbd~p1NDrL2`!d zQSgJ3P0cRoyCwWTdJlrC>J^D>4h%ipy~ecjGzZ_OFKa>cH!uvM(d-V3_7W|h$X!_} zrXn-d3PDs9nD=?7^|uKn+zX7c(JgTCOhjRfd?U&h+PcVW^K8$(O69_6Okm?PS!oFs z=qXR#thkcD{m}yA-{=5DX?m`chGH@Swwep3Sa?qX&ixyr%nbRcKgMo&V))^gxu?~S z3eY}Z&eA=2ukgGptdb%3mCyrn;FlOnpRmh};!49LK$scr^Dyp#;RZLRtgxIR`i`D{ zO{)}CN!oD3`ajkRlYalHDtlq54}H9bU&0}F@gUX8lx%yp@|kTKK4@ycfS@Z!H4;_v z!rQzfiIXXyfWBiNtXIg{P_A*@8W#)D%{NV4g;UtI=DyTY8d%r}&ABY!NEJXjHA1bsGW zLbIFnE6^hNca2z!RoK;P^GyM0t%w!WH}z%dCv2Da-h%GaI{(dGH`H*s-X=PrEb@%3 z81M|*W;H@PJ(BF_?GOvspx=rI69C+$o>|f1gU3^tC@?$ow+t)};u`8F-#>%=Gc4p{ zdAb?|z0AS(Q*+X6?NkZ<99Jfl*9;Oc_j*zv>Z23L zhTy5!AE2I@zi0=1hP_T`Ej<{`t<_MwZxY&&C^_ilFtnxzn$GK2^*55?JASwMM&yAz z_*UK6#=P&`E&S8GueY&~a7g*S|I23DWb1bZ85wrL@wD=vZFyeKZ`n{!~Cr+)^C?%k~<8@`6jJJ^1Is z)2Ye_?xzG+6O~f@zeKGTf<+XLgYmT#I1{%(8P%7ert#R;s<*duhO8g_0s%#)1DsQy ztkwnQy}%(~=4>gw!7HYfH(+VmGH?s!t~!7A?ua33E;HSX>Gf_clM(6R*5z}1p#(${ z?C0$f3l(C3iOU4xzZM|7FhLIiNU5m#K*&=t3qVN7#Z2W} zJH3~Yw^8PD=wsFc5PDwhWV|G9fADdj?kgeEYD6HFTJ#C8OjUGnA0gr*$>NJ(P_q&> zfk-v`NgIRm5Yz;U{p{Y)A|g`K&nksuai?Gzh~y&N$J1BO#Z}qV71>RVwhol(NX2+r zO#tj>pa9PQ?Ay^DgyJh`ns;+RJh7n7#8=XDK)IkCI)1=Xy})$A6I&`^ZmwZ(R3Z6h zuXQ#lXjWm5Puo@c0$biU;9|ELtdZIbiDG*CygF4$52))9eLg#Ot8w-}qwj9o_<5>n^LMx#Ko;?F_z|ug2 za4lfrjuPYUV9tOC(UX#QsXLj`FsYo9Z15~{VC>|Dt3%O^thhm+?~S7H z934XIq+4%>Q}YA2q0!0<>0^V+{hz3q_f{j9AJ{vnSZ(MA1W4_yvMWUBS#x9--Q%D4 zvYWVIwX7Z8e-#f^z-Jb#d}KMS49nS&RwaC}*yBojN_0%h@G<1#;?Mr(zjR7eT7_iGAbzK`k6okFFXa)rL)Ey|sY1y*@RW#Sv5+ zmoDktl1Pp(vC-oov}m$UA`Y!Pw+S4c4I`J57Yb>PJd`+1bov!Yw#=Uw0g zdrXtCLpalyuOcEKU+WJJ@sDup(-va3qbXwkltB|QP0TMhMtvMi{y46ffHpQ1wTLYV zNLVzM(l|w=l6_0`VUj-vQz~k6JO@%C6<%}_FbuBkK3UJfrcPt6Nt#AQ^Yfp{GR{Yb zD0NX``2!Oi9fw&ds#O+Y#S~_*Q+h|RqBuo`f=FQeTygIdHyY)@w<3g(r3aWHhz{GG zeLceTOu+e~+I7LN%VUk=UWq@zO%%>I3x(Dl1@A@St0vlKMV<|BtTLr|MSg92aEwrq3*= z%&*gMYQ=!QsTCtQboBi<0cspXI1ZsUfoSh zQbC7-^Du#mTj<}PjE}0L`Cz`XfBO;xkpg+Tsh9Rw217_LUzavEHXcCu`kqNSxVU71 z*a*dw%;P^42OmE3auh|%t-r@>)4Iu$)Q*OK5%s6r7g zuNb=Pz?2;h14XVlVTRDP`QyiZ)L$?C38w+>kS+rI8c5h5~T6gUQc3t*icbJ@F!^I98&#M#bulXmw{RaiQMDbM;X{b-XTkfC5PTx2x= zG+U;=i=L8bcbYJ}=Z6@>x8lh2WSDCk?&}9Iumk_r$IZ5&&`{~PBn~V`e{@$mjpFuf zqrEz^-zHx3-#<(cfl-V&Qw9U*?5{2S{t75UFr`AVClTQ>V|?L6Bii@uC@@aQzA5C` z3S_>#UB+|d{|XP*_!lYsTnNy^{45ymsQiaOot)4wcJIlPCl5Tfrh^c=$^7_d5yagF zp5@%baAwJ1k1`9o%VOloWq%M_s^CHV{d50|14`lTy;jHX%^#7!t zIM^^Sn9Kq+3!t&i4wJ;ZUgK5o zC%ywrjeBInAYSt!2=lqic~``0;gZ#Sub_I(mVb1z%5GSL;VDI009-4a;1?!iP~|X?*WFkGIob!YjJ;qydHZO?t;)55aPxfm$=0W9 zV(@S}BtApj89NM8@BbaPoBS`f|Bu_<7=<`_$CpsAXnw+fPi3*_CY?Fm@p5*uOTEvj z*ew6xB3_9XB&x)BDmx@-r2pPm`LgU1hEXEv^_9dnTwogpWb%Q`B3V#FXA#GT$3>y+ z`%PHT{JI|x5-)y`TtDD(6?1Clu*Q12j*AMd{4xfU=+S|e1lw&do(7z}*3hCq$9 zPiU@QA)IyGc+;%ynQrwXhB4oRyNJmZ-$cC8736Z`r`-X1N1_Az>pUS%`zMZUfNFsl z_WyHrLhciM$tm^HDJyvSGm2CHeVI8@y{f9}BbY_m6)(*H?=Ofq6Mz6*FzV1OAxSP@ zO(X&{a~`rR2?9Pq^tnOLnX|^;*gL{r2=ypr@;15u`DBsq#d#l9N7es0EdLT-{P`OzNh!(r&YOjT2_=pqL{BAYs??bZI0btE zAvXg*IZUb|MomYt{eOJDbyU=O-^UHIgwi4*HH1a0l;n_tAl+RCA>A>IfC!3|0xHst zlt_1pq%;gMl*9l715yJF@qB0Zy6)?`pZh$|AMV+6_UtbF>idcJ`}JP4>wRBRDa6Hm z-M$BAjslPXd!YCe@t6kgFqBAYqf_ncmkdnZ#@}ULGFNV@8j6V)zBqonyr7#79-&rP zFlEmjGWVOeJRsN(kQR1lXCgi5f}_OnXTM3I`h`xVJ=%TtY&#zrftR!g_C23aGYwqe zCx!++ANmN0>>{p9Hek6WJFmre7FtK?aWZJMQIk^ZIK&?22ehIqgv84uDr_Uqei;ss zVwVf9^Wk+n^{jYEqEj&cJnSt<;mmHM3v!rngi3bLo3w1QU;E#Jqkk(u?gH-jzrN!j zpI%^LS71>o==;YYvAc$Xdz@1CrN! zeSlyyXRgfQ0-<=}Uqy|l3t@PFORN#_d1Hj&@xS%UzfzJb%^ySjVv62qcgKu z!b2xQw!?Mo z*Ajp2v{l1`a-(L zYdXDa${ON(KE}pEZjKzcYn}x`OnC>BbXR!wLbz@^^ly$M#Q;A1 zB>@TNErF76=t5n6ARbBqsgBS{{MY$$-7}uy$0(brQ#X`14DQS5h>_IUisl| z02kEtI7YC)59u}h`VfQ^KV7f!QsKz$`}A2_e*<}|#(Bx0_S2Cpj?DR;7?mi-x%VHR`_Ab^>f9~iXpP%khZAVHk)ghCo~ zlS`v{08;6}GL>?bGdx?5K5ZpxUwVZvp8l zSYhk_7woV0Ea2L87juBY3+>7N!uYf|IaLhO@EA~4bOxl4y@j1yGozrM7Di>m(t+Ua z)ApWyjF?$q|9KWeNK)BWPPuYUnwA=77xTFy86?4Vpc-`QCO}%F-jdjCi~a2X;x_)5 zUhD7kmv$8%f;4B**1(zS7v<3zls(e`Zq^${Mn)w5*yq2J>HmD(*u&S6KT?F^aWt#= zrW+_>*1?fmN13%z@ucq&nkwyiJZap0q644^c}^Rl{{TOr1lNdJso8F3b;+o9TYd?~ zV-_P_c}wAj?ZcNK=Lz4xgEh!V<3Yq7r$ciQ|9BfgOcm*%$Jcn_*bCt}9O)nw%;76^ zzF>%sgT_1+PdJolYc@vGxx)`|Zz%@6=U#Utg&QVJX{^>>RCN*!~%`kJ_mZODGxsydG1TX3Loe{tKqag89a#T~?kp zos$j!#W^3>sn5Voq8g~czH#yfA83W2DE_Nccms-ba8CcLTwhuoPxpFZ(ewfI-Rpp! zK=LC8ycDlK?Nu!|+cn)vxNpGBYu57?ymf1Lv}+%z>~rN~E1%Ao^bZ=B^Yz}-=UC?C z;Up=y7R=g>pMebHCS!tTBs^B|fsNUlMOi{vqixDe{lZZOM;MW=2U@*{q~LC<6PbHTDrCOWXeVz5oR zA@50DFFx-|5_VA{f5FSd?=)FYPS0nN2410OCRR1>EZ@sUUv7&QmxLt9g2~C~%4F<2 z@XoO0V1f69$lzOnjhl=AE@RfFL?T+&$D|^CFg|YO9E~XRcXvH4s$v_Vo*_Jk)L}rO z`u02Z&<0jLhW^Ad);hY0hH&?UImYsa#p{%&l4)p1ei>TgA(j4?Czyprb7=c6PcR1CIAR;Fh`F|T;B@Z%LmO#|b6O|}hWop6~! zP751C7=&J?9Zcptq63vNqk5}=S+zC@BJKeh#6aC<`;A%-nwFM^bS<-NTAQkPZXTNu zxlzt8?PvXMPz!pdgpW$C_eSe>yry&jfA)7*)WgKAfuAIw zWd{9C(zrdqK$QQSnfdafWJ?5x&xd>+Bv3bB?*!NEBRbA+5t`<*lF8bUXi_Pa775zr z3NERh0!;c68NZl4-=%|44Hc8MLCcER7bzP&u)y^j3n0T5z*AU7p7w~%o)hr+gGHXI zP3$~a$TZnNb?YfU``^<%Q^nySS0M7%t(W>Nn9Ec5__H;k4aI$H$QVAiX$s+@T49L0 zZXUtG6b0_ay`clek(^UY#5}dcE-fq;PUL#gDQxsrVk~bdz`;LG7!vgq0@y_@KeOtL zt+D~99*;W9UzPNeJ;mjMk^`@|!h0Y!dC$JWtSKphLYpgprR{gKv7GqMVV811o5RXf z=<|2M7LV}}y(4T{O@Nj)R-nUuvJ?yTngKPN8n;T!4RUhw?-dotXssS|E(Cb{^!Rc~})}Pn3MY7=yLec-6&L%{-o-iF^(kVTZ%bseRmb z3%a^UPVNwmh{d(~8)VV zRQ(8`h`O|o%(va+gynpTssLR zCME_}tJ!NUdC0EK5ceg39zSmnCl~FMtqnT9ud=z+Snsv2U;xG#h9#yT=qy%b=JvJ! ztHj3lX8&ll+h`0h`GE22>7e)?JqjOt2cWl+he@e2{=<(Wefe{oP`?MtXfGE(?A9{* zp6G!RQUVy?LWhPlR$_BdRoi!v`$R5q&;?=@#x96g*Z|Pa_@zfxXsDa5(@E!cuEa@ybefmZTIhH{wO>hYmh7=`Fo*nirNshZKHA|tw0HhB3( zEC80c3N8AI+21Q0pGcMZy2PJ@YAencLPYQ&DX>oy(2r6;S*yT4OTyHD{)ZeUSC@zr z0ZVLY)w~I!;#{3lHScEX`1F=%v$sx*Tdg^soq#!cWtV53<>+C`Tvv%dsUsLb<@YLx zT!2WQBjf=t_VSxYm?dVKa#sh3M^sc){JZ0kuteZ1a}N@=ou8OUV&FI4c~nk)TnmCw zWy=B%HiiK~rn{%-jTHnMZ0?!<>OXqZ|JC^8Gn>G2>x@kY7?)S>u07gwt?hy0F5x` zmMm;AqwF9;NP9kBFEOwP0_eP-@EbI+TDxl>CNGct0m45e4N|QFu{o~10BPPAK7h!CRg=z*RjI&@_p&U?G8v4U-2 z7{X_OWN&l38nwN6xg%?P3w!rvtApADXYEbT6<2AGHz2G5+f#Mz4-A>+QgyrZ6fAp*uV#z;gB&aepv-`lbEGzdz_LbCmEb{QSR@xX+sMG_Z zUQnpG(7M7Xxxm zFF$ZgW*9Wl9R2x=Yubqn=A7YkLWCkh0TECbCLVFe7L)QCgfEE@$ z@X(Z1A3zTWUn`<|I-A0mLGvfH{Nn)CJKt?3;hj3+lXHMir7|e9Q3sTmTyVF9>25vF zaGa>d6Ozh^Gpe>xatX~KCoUO;g%XpH1YdN|aB6tVIB?MHU6y zJWGyKl=*QqGI_W9%2Phw$v5O)XZ>s&2ohL(GQUhDN*oL0pUHO$7JCgSZB+do){LZyM zJ{_-bi)=EZ)=BC&;dy?TBGU7mdAxL`cT1NSk;rXE#Vl@n$=R|htT#ch3l+y}z{?v~ z#!+JNUB{O)uebi`mqOd{-Y2e3W!d#NcN?eUqhSKzy_KOCGDzbNubPXvx44sQ)dR2< z%(DK&jE_ix`bJvDWj`F+3H4ayzHhaqr;Z`&KIK$=y>@8w{mEr@ z*o%%Amlzot=Sa$9O$eCmwc8XLnUv&PKqhf!dhp33gey4BgHL(kW5 zVsCC#Jp0AG)l_T+VzgD>@*%DKgjgy-1mSsX_xf>SURx z?8nR-X`Vr=?%?_LD8C^BU3Q1y zXBxY?i$qO4zNOOqvrPe%zuUs%!(av0AqqiMb)Ktv16vKljn||6GHe>LHvqKvI(9f) z&o#|rD9ar|Ji-mpYnkyDFOM)w~b|b{$A&bg&AjlTb zolbjU{O!dCaap$&UsC`g(RCfV^B1kt*HvXi{db?3R@&22lYAY z=Qtbg!LGfR*7z!-pZDbY#z-m4mhrXzNHKnlVk{7{3wa)2R_Vi0uyg^={EllXTrS3^s#a?sc5C4(mSq(l z&zo4*e-Lx1sWzj66w=*I;4w%dWg@{s24L(+_k=+fU<@c|52F+xn9J65ZrCU-l5cwL zCA!Z*Z8|ybws6u;OwQ6TcUPGMJL6aR<_Mi-%?4 z&1)b)B@Fbdp4Vjm$`9UPBZ!Y}CFYNbvOkUIR>7C*{w!HXVPRnolizF_p;;N6I8Hv= zKP`4$RAF8+1P)$fcFF@Kv37uJx-&@8wY$4(y9mHQezQ%1zO(I(@on!y#GI$yr1;5- zspM{ehL}YKvvfxNC>EPy8t3uVxZL)Mv-7WQ9tz`?!Sr-c%RO|RZyxV~DV_SR4Ta3_ zf#NRr{Y`b<^^x4;rpQnqPt-te(DCk{rjX{leZ(+3YucGVa}Vd4tXq>AnY8a3($@X= z9`vqv9kq*j|-@UmUwVB8)R6m-9$vKXC2IjO65V;-h zEcWjfaQWHUFNb=EFC=Q`db1>>Sw)hskH8-!3YsLL(GL($-;@bqaR)o#;>bSJOi}N7 ze{0F9?PA>Sa1;4uX0<2vWA^!YfZnoMH;n(p!K#5!0O_$wH*@iHDn$8#!J-G?5={eM zH=WxaJwpENrqtdiGzdQX9waZ5(*yeT+H-J_aQ)~djd5F+)tnt(xp?jOqq!iK%W%kW zaV>G4D+U`vWp(-)?UUN9o{u^Ebx@lIg5qo0$+^CwY5zh7437iZ{(tPMXT-xwWVKPgA2c4;UTRX z+FJ=Sji9^-{H0m$vkeL77DwI@Drt6*#)mRi*rgrxA)*Dt za)LN}g>EmCGWSsQDMC#^V&C|nAh`IAX9f|Gp-VUg?57sYR4d))|7TxMJ=%A(9Bc8K&sEJ z6@ovHOP6Hb`wegkbyUFA@_OdC<$hZ8yXgbw_OpfKumI#5gf zLuAGp^lno+yF={e9f26zKVmK@Xv~h&e2nn)#c_RNdiuw~$Gnz#T%-?jz>edqu~b}? zy7K_)yfC!$uG8eC_Ehh9_s9g#Ph${(1vp_^;6tZC{hi&vg>$AV=fSkKj&7y=nENsz z0a=jJqE($oc;{+~S&eb>MvcxeG%5MF3WOChJZMk!ZK3d7Hh!jvBRn=B=6%v_8yo(* z3vjIMwGV?DGv{~@<;gZ}cSb@M*qBf2ABz>&eF*aCq6gAsih!r%>081(IpGQcX?9&P zI&GoEg(|V^tShl11~fR>$^N4J!~Jk<-j^>d)R(N2DAKgz&L61sGqf&*l)vph`|+RM zk)lEzj+X{YT`IkJ2S>k$&_+LVe!xa`!>^pHbN%-^8t}7s<3mXyf?d&{R6|I^{H2y< zxpv2;kBk&u^>Bu4Jc=h2jT$#WX|imXA0n7LkPrSj?q2uHfX)0C4ukjGAHIE4$+<|3 zGXq>VpX@}>)^qFgcbzGh$hHvta~VY{?C|}lYx1~i_KEQ?T!6VZA^O68n+ zEi!8i1|^H#2WfMo#!2#dAe}4$P4lMK7R%#8?ygtkU{)G&<99eLF+hnwi|XB{`d5R5 zwz-2lJ?0Utzd=yhYBkM{C|YFs1PD33;*;_5kO%ktho8BS>r7@2x|J3gl<}x@j458> z%)h_U5ODl$M;saKW&zQn!a5PT1ew&>ltjbus-01-K$ZdLPwnkt=a-oJ zKR6xSr>sVmA%^=cu(C|^2odVI{DQ9SV!)C^_(C2$^qr++e6cKPK6t93QY%o((!xEa z_*4FFb};bjoHonJ{9s(>D-8tU!sZd@e{f1>s;83CrtUD{7V{<&_k(6oy-Ta(`dxpq z*qNpifu8d?<*f-njYv_1fkmkaGV5%!3g-nYxI~MXt?sfe_4IKqrHhQ)KZ0d6<1)%6 z-LDY7t^eBVy(BAdrbI37I2w(fHT4?nF*;=*L$g2dp(5A1>xN`4?Z7$wYQF2j;)l}u zI-7A5A+CqH?oD7fHNa6y1dKH6r411tngta`rF0(j&VMStdzTI#I0sVvZX>OX*w@F& zxwut!dI#QtvW(f>v!M8yF_++G6bz`iAM*gn4_(^uWtV*!Z8(S6@LuxQZ_sfn?FhWK z%~^>zYM@_kpX@xpN^%dxxEanZ{VFv0cwRqGk8x$C#`5JzP0LRxe9fk6F*@)KPiM>V zjM9W1TX_!=hXJTqL3*_pX`k(B^KGH&cJEJ=#Qw3>wXqxXnA(SUXc_pJ(y2T(nFFY$k!pAbs(>#8c6dFGC16W1Xz> z_e1J|KNOv2b;KrUG&fr7%h5G1f0IHigQ{R#c|RnO4BJ|-h&p=yI$$%5kZChk9=Rj0 zPLX`p?kxv%$)KjV;cA#h$@D{)l=V+amoQbB-3gKFk$(o&%vgxw*b*undp#|4jqYHL z+*|IQzZx$zzN(l>2ElCkRCswn=Cki+e0_PY06B;~j4w zt(nA_Lotk^qLjLal`lq;!~Iu*t6*@I$ejB6_Hd&B0#RxZ!O(BsUWbWCoDU7qk-(7p zCog}bOS;^ua@=U+@w{ujbLKn$Av=}MLK1fN!2^z~mkBZ-t8tk~x^$QxqtIRMnbMBR zMqZ=^y^ck&0j4NgC{60yU>vY-fiHq4(7JgK$CbBbYAS-<8)vMzbYjYQ_?<68f&t=y!E4T=er zBqOkY%o(?+9+9@i1}GtlP!zP;hnWvyb}Tt}Hoj3mVcc-Xq)f{fir2b4g<=$^UZ0Q2 z(%g&*xEQqbJ(6It^sNngd*ICnQlS=7#?gj{ZBAooEAe2cBjl*b-RvpL6V45qUyw8J z3${6x1axrEfggMglrIpMBANztaIWv{wihg=kwx&BVBifdvd4QK1dGHSAP@BrC8xL* z1Y7VxdcDgj#2fq-DZD{(Ir4E8wSmj;;Nf}~R_u~@L=Hjm_)MG52g$Jal|;`C zM%y!l#t09ZsCO=QPIe0Xsw`Ed7t$;%xBjB0v3W@;%riD+;uixV&=yz`j=@f6p?6G| z9ehDD6ZZ5CPi;D#`T(p=1i1QIJfKb!#mfr|8AOF{Ae8WjgZsXoFK4dabftsIE}F5Q zLmmQ#nMs%*`TJSuT>;2kYW}$zLorwr|n})Wsw#_iA0NB0ZFrv*&(Q z5!N{9w_Ki;z0j_?$kjvixbDeckqEY|fq2YeF%z*f+$&UB=Lajz%DG=t^dQch+fj@H z0|(vPWqH$WE$6+}dJ!F7JTH|nT`~gHBTU7+IAh-|r8iek;b)=Bg`8NUVq=gE z6A5yr|LcM%wqm#D(nn_qmOCLEqVM;9b6W-5Ve=9s4IGmesKjC<-Kpa|@?R%Xst0uM zE%)dR?H(6FU8w6iM<6(ahg+UNk?+W&#cg}+PuN(o4mqac#rm$-&x@;lFr$wF<{w4X z#dcGx<4CW%HO8=~9x+`PesUw-X31eYNl_$lSGqS*So~@4r_VoQllu!_feWR9;Z~@^ zZ~opZI5mI^#X+{1QjZfK+}C}+r9^VDHv!@Ll3WFp-c-wIwEEuauk32)nfK9lY`~dP zFmmg#;<-M^pFVN}aT~vG1Aw+TYBYx5gP8L^7q+DY34(LGu_+RsyMvYj;FFix|5^>AS9InboF=o30iycJA6?eM zGMA3lw%7D#h1wzQDPN#YNyQ0JSHkw+jmA$H$)^TV>tAN?+%vOYUKj?s>NXGMwoFUC z1U9J#Z+$Ct=?Z0sxRg)2CW|=u4`s+V{q&N(BOM;weO3!lrB~OaJa|!jMtWA@ss*Wk zOZvGRStb4#XJ*)#ma!Ir6T8>$K1e@{*h>~Dz>Rom07%SY)q`(&VQLkJO$GH;qTZX6 z@j#YdNL1HQ^`w+z4gbUm6_DG20{N+>w9&7+*v^z9!xA;nm#-*i-Ww$)-`4zeH^lRg z;uu<}KuhlbP(664v3Cck;uaRH2kM|co5tsC*^~@J&U1|t^n8Zza4J$cyF6CS z(&>C8WbX{XDj*2ZP{IsPDzm4EzO37ul`&80^Q%=fCNqyg_rCx-#Xn5NP_Ry87;Ex9 zzUK_QOC*6*&xhx`OD>B#O@;>etgDkh7g)IyRB{&Qfr@|xFBHJbEW>IcXInI4BN?>h7l4PQNcA_5-N9cI_|fJ^#?UHu!BwqBdPev)Hi1 zZP~)V(wieoBW8!U;6E?84z@6lni4$c%ICCJ)wl)apFbcJ4Uw-e-Z|LOKfEE+y+-67_{!{cs7OV{tV|1zEV zi<6V+^F`H!l{QYd?SzKzmPQ`v6x`WeU|b-0B=TMNnX3?1Cr*-FUY+i?=DUK+Wqqkq z;&pX(f7%;9t$*M%5@Z&4Nzq)!ZqKKW?q(14?n5W3?z+7+ArLUFTo6^ze*TWj1G?zxKYHh@c^(-hi=_UsrX+ug zO^5xb(360*I8OaibCYRkO)TIuv;!qSP_^MZlM`gqQ6zqd&f`9IiaU|(4&&n#FVu)S zWUWgV*OIkN5ce>H#RZU_&DHHhvRmTr9305E)C@ouJpFQpA8rwm6RON5eZntp9#URc z>>znJHeBvNy)o%PcEEN|IRaI%-q`(h0(bY;Ur;}lS<>j6UG*CFU5{u_!82}l*VF!F zH#K<%M8l922Het2Q-GcyW#={0zZ&H9fCewiz7o}avNct4JL~5+4qgb4-_Sz~R>mmj zbSdAMFrRwgZB3xrS!O-8FJj=YjY>JLoktC(4{p(9!WY|#i6lVAJ%dLTxEILV(`zbg z7rT8z=CPk;rF=GlkRu3i#$!bJk7P~@cfo#p=Vc=3+QRYptp3*^Ffp6R!DG5=LzPNQ zl*gb~KLwNLi)gOzbP0FuIH#BQS{SnUg*7+dX*myNu36VKJQNgpHoz?Dw|G4&Y$0O1 z*>o%ueEb-|1i(p9lNam*AE|mkuF`Q)f12(O1(W=}-?;=A2*(dhfL90guu|*C11kaP z_;0}`xHEwK+O3s-)6-D1GfetS70_Rs7@OJt+{6;*9SxdpsQ_bU!P_b#iE-D5za;nb znw|%bfutb($>a{Q>@NUOczJtU3k-`h@KPo)g|kOblz5%&J0z`};)0w&o>r^GkcEZC z`p#lUvh!8$|5+3t0aZKRyAf(Fc0;TVF0(1WVOGYhr8RgocfHVUUg6AX)pL!fk#sH1t9lP zHiKdr&@Yqxy!Nsj`h4yG{WBRa*MJ0IeehjmIK~U?K<1xk=?a*~Vwo67qiO~k7o54mGYMcmsS{&EiGu(#_4%0*wATG5+i)KrbQ(^mdUn|bszL-Z45(ss2TosGXQ%Vu+O{(c|18pL=pgY z|2lVF?DK3x$STG8tvAREJhFr=lm~B;_?t%=H@O3RC_v$rSEoVqmouo{6w|mRAs+CP z{q_Cdo#aHrfGjN=>`iE(`t#>& ztV)B+Y<;V+jiO zVIgl=#9h_~sKbcK8Td0Ky*J#XQutc?!-2{xxp;x`U%}wP?JCQ`NKn3N{GVUq0qjB` zT=vAs^9u*r^r!D2YAra7gwnXc%*?EUX1>;)TV^(7;r4env~;Ft z>vmKTB;=^MmeU(*ENu_)uMpr%wk52{F3aRdJdyk%{X;V6!R~eqSTQn=D(g%Akeco? z#BkrFUY4B(bG^u$n_*)QBCAzkU&NdrI6`2G)!9_>2Owj5xl#staVp%WEKt`1h}ube zk*dnP?B1(wV5j64$94B^9Ga#ob}8GH!dmXg4o<;b=`x#){wQeiwShqotf@DbWk((e zST=r|4>Vl?qU)47hv6*c(~3?f9=v;vPPP_u_uHGcAuStMSFK#N#NUCc|DAL4_wOux z&WJzIp1A6LSf8pB@56O(-8z0eT2*K?6AelU_S|S|R{R$)Zqm3~I1-H6^Z)(85_P*R z*LNw@6OmA40D;Z7yAeCD*CMn*ToD!ZUq6&F+}|yo$?IhOcC1Ug`Ux8+KH}oEKN)0H zlL9A;L--H_>P@iQy8|@B(-Lm5K-3*9B_-t&kpSg0Dt+SitJadWLMvUC1YySu5ILzp z-|7DT#-k$uGn=N6ID!4GMa@5J! zOf^1Ne9RRJ!P!WicOEF^foGQstMLx_5>!$88FGXq+f&`d+db0$yV|cQt`~qklFssZ z%f)%$b{LS?Dvt%#TkkA@&lPQ176Xv>4x#d|#FUAW(bi=MH9`Qxu_cmuYZs^#23HL( z-UBP7>K*H7rc;^Lc>-y2TcUGAeBnAur;IWB&&yEQcb3qjH{v@FQ=wDQxMyGC*fCR$598K008x&UgLZY|~Np?sjYnMg=Y<$D1Db5rVE>w6eez>C6;4%O2v~=eyS+ zRvOoT;CQ>p;m)5NyLW=BaN|&`sx#P%_p;B=zY&3NqJKI!i~^Io$lsTirw^v;!!Jp` z_$E^2%sKA86QXp5*pYJpe0-mBVB=RGLT_J8l$h0Rfk`h3`B*go3Mg51DPf2ryYO^Y zAi|MI)B<)*FD?iwvWh6q)iioX#S*SM-_3!l?1qj0R$q}Fc}&l590#N%S9NgZ9OKtU zH093$#i-k}cxtH1$q4`XF2lZ5PNnTBW+)zgDay4I+|gn@Lx@(jP9=rO$HKn(2~Q-o zau|bmvDOvV6T7rESspfHE%UZeFaNvTkE~I!HIA`Yt|u%8E?v*B{3*gDC1YL+ezE<@ zqETRPs5DdKit@ZdMz-K=1s2Bu5D^Q3u3l3#ekD^)jAdqcsj>`T1}qX4Jfk7h`U(&d z)D##et~7lJ69yloxEjS5)SFTX!AFavU$v{bZk};ET&sil{Jx~IllJ%kU90DG-?0#ZF1EMpn6{i`-9o??)zLP@zs~V zv+@M)Fs~<%srr%mQ807dX9_d-i>~4x$;fTBl%-h@8!TO;c;UyIHXZXH-{_=phyER zWAB!d5BI97yuxieF#wq;UU8!TPo)X&J=T6MX(U$zWCqe_bTqVkZdg$@_gs?o|GvCD zTr2=sWbJYo#RREoDV>p=M?4xEBB1LIR!bL@L4B+&cu`3AM|CTko%DTU(s%0V+{d5a zl3x1;Pj^YHCp%flMj1ESX>&SHdm&w?MI7qpldG%NUbH@Si70?m5G+itk)lAQ%^+(C z+Wnx$_q`Wd>{nI}QDLRp9RbnD0Xu|s_VK?Hz#v4H>IQtxeMSA_2vt^#^|?YLyy7)T zQvG`&+>~|tc<3jP&HPh^^Qd6Br)Q_9lW#t_ar4PdhAic|faS7?wU;z1H-wcW4?~V# zwW^$akq;vo2DOjF&v)1P4aO^_@zq=PA08~HEUn4b^745a zA*^H*cVSIuVTd*dvOm;*1V^X$5_0&z?)fUyyHM*coSwiZm~O3`O{n_P?drPJ z25jYeB>uagD8Albz+>6?0J>fNO{^7m?E?~{jRkMJoE0QLr98hY0XuyW zlLoE7{c=RU6vZbe+tH=>_S$O?`09_k1PMKc-lUr>8vCEsY6fOes@Q8hy5H|YRz=_A zLXbih-}xc8y}ynvuTIB_@y{y=-|EkluG{s1#VaVU?Z;Ojx7RY4?!Znc68KaElc9F^ zwxK|WWLbN~HhA@i1QN49T#>*Xs5#eSzi3uOv{G((~!2;Mjjlq_CU&x4&;u&CF_q1FhNm#Y_YB9iHC(GaTyd zOuWF!Q0ZOd`>=w@_nuedDbzI8G~as;NRSftT)zzd=1!z4!?li5r#Xv?Iae!c{TX4A zez~^&{hg-4W7d?7uNxa_Y2bns;(9)Cmw8jNO4UE#kr5eU%Y_!8#DnAEtW&R_#-R&-R&DxPUz zQ!H^Dt}ipK+d^G@Dlf5Y6#=O9w}VgiP_}F+aJe|9!wyZ}q15@wuw{Zs1WJVn>b)`M z9@5l)1V(NRpSP~eDt3Ss-xQju%5D0aO&E@%sB^S~8u|j93_iF!V=XvL!|W`(rNe@1 zx>VK6T{RS9u%X!(bThsv-MBJ2%f%LwOx+w+8<~Lp$YDjRFk2vbY9PmYTTn8KxK-?n z%4MQ=K|MHq7Pzs$KHBDHg=#jxfJ2pQV}Ga-nV&S3wsZhV)8ZP+6uu!SJS&<#k999G z$mBv&TfM>&WIeQ{#!6Lh*#2Uv_Tt2<-|VejXz=}b?(#4Q2<2XE9GNhNMQ|?90 zh}+daF6|ub34=`S4Xy&)QU7UzvtMA5RN1rjqQuzJ#X^3qnK!Lfn5q3z7XG1T>KwnJ z>f-5@fiFz77$Q|i(*vewbPO(6K$g+YRa|I&@}uJ5JupPA0DXl?R}355ub)N*1;jq| z7=Ik!W1ZTKq0R{hV%^iCS)Hj3SL4%W#69@5ukR0p3L~E!_>$O36_k zflHn70VypE4LkV5q*OHKWRY(lGvl1`#Q`FPga$9Xqg=Z;dC&a7Om-`eg5Fiwl-=0 zT7yY)TJkBEzmDw+-8 zb+5nVmU;RuHZx3)mv8iy`N(CKmAok2b+Hmc&Q}Gu$ed5oxqL}e&xE}&eS%Hh+U_C) zSd-Faj4YXqFL(l}ISLEMbDAh&o(_{;1g}(TsiEM@C5tpVDwz-i%}N!Rg4K5>G~JaE zK_b|=>t`NRLR;FsOIBzCSI<}4VX0e6#nmCOE)VBTgO9w{nIz&YkfR zCs+=`!sD4ahGt2UGa;sqketpCgI74C7&qwpPCKk5H!Hl@Zq)Wq{b=~V9zN!F*g=<( zTWPDg{E>k8ylv-|k8U^r$*>Y(M+O=WD#t zHChj=@+&1_t(^Z^Q&WFIJMJTdgdm?QEx_Mj{H~_nl=xxMayafOi+w>=1D-9kM3YnZ zXBnfN#w-TtZ#M8881d_U1_#8|p_#ye>7U$I;V=q0zgM`OF#MwgOPqK<#D5Ihrg;#G zvsGQF&~XOb81-=V!qk{)c?U|eD)`6=b@Fjp+VQlItT6VrM)H%Ixqu=k`dmXj(?0pF zqRP9jN&F_}ss*0w%=A01Gu6LJ#50|=nI4y2Z8B~>`XFM5F|B@Gs1yK3ZlQ6$?6+i`XJw3rB?b{K&UH@I%jqgjmS21Pgl>_X- zJEvR?Le~UV6nv{L9QGacYSOC_Wux7iY$ub3Emd>BFo^0){^V250uknri$5K=>!heE zXUVY#=81ghYf9K4aG(%yB-3CzsM}%i#pX~4fwf}U zlM~l6g$|fAqP@W}KN}`GYD6yTbPxINy09r|V_&TFCjPmC9T!xw!O38eOVb2AL)+s; zAJLafj$01hs{YYBy?seZ&ZfY4vSpA_d>YZzC3%oDz(7YNo+w6;U&rcMx7=C;0 z&Z_BOPX~^2X3|#QREp(nN47Rc6eHE?X9Y?fr#|q&p7pUEsVlcNrkUYhzs9LQD|2gW zPSYxD&}qsu%=CJSm_Q}9I%!|PDXC~ML~_f;RHtxUlHL4&J%hdNuzP$KCJLC>4zU$6K$D-AS>hxu=Z&hChC@dk>$sB_%cgLSL^%y4jU&O5H3Q=C z^PrhZhYvFdz5{xMby(@%-=8|+s`}lDEbUlWRm+Hl(6nGZ-ECRrT1Yea7Ar;nV8XbX zRm>3oHYKQW!lk*)e8xhnNW7Wr48{FDRz0^|D`5i(#F)duC)isR{(6H#K@HZ^wtb&u zKYS@HbF(N3dVRq1)HUX_4G6S$g&)J=<@*lzCr_T5nUh0gVi|fUDY1dR>)UDQ^JVNz z=z7#_b)nt!de8L~$y=~#3Ky~SHBLHYR*hsC3CFeeZR3VPOF^qnOdZOSamZ=Wg7`v+ z0p1h77XaI+Dcf^2Jg>Z5!H*Ljtn()J3bw%60m165)c$ws!&DF4dSktdOwE8sEj7Vq zRARs{=LHt>4p|Zo>2}zWd@cOxVsPacC?t^q1Xl2~Di*IHju6u~1p=|+e9-c1_!Hp( zB)+(1tn_~#1zn&sSeZ1=25vVcfrWL=#A}Sluc8?Y5eq(aRGKM70Xt2t4FC8W0d88*E246?gSHHmUVp)@Q%Hm*4 zyUx{aCs${h7GDMmTA-5>rNFzOfhzOwBK6r_P)UMn5rRXAMs9FjCOr+;WYP5k_=CjY z)3#>i)+KC{hiMHDT_G}vbMo!JK&jZDwR1mSyFui1^-8CmCVV$jzQq!f#kxU)X@DQm z%}V&sxUCB85O~#=r!UEz?sOQo1fN-}Xa3NAg;OnVB=#O3Q4{dD)oX!Ot#kg*RSB-t z`({;#2)czX>^3NlA1@KbKo{v|jo|ZYE zEU?V@EjwYoYtIN4Ozmf$S2q2bnE2m6&z4UmjXjtM6@#qji7aJugpZ2wF`XGLhP!+h z98C_irBv+F_P~Vk&kw`RfowUfEO4ngY}%YKbFH|*U7Qb=(8h^*OX9kqF5a+%iYL8} z;9w^Ye4*Y^SIz_#8=GY|*D#?S0^aki3I*f7E$!1?!u3+#^Z# z$$D_P+cnWqw7T3AF_q=q<^2D!_vZ0XuKypfa;Qi;l@y_U6YAKGU8_ox3R%Wfj&+PB z#$e1y$SFlDMF=U|7~3pn7+d9(?94EWB{3K?qcDRpJlCA_UC#IS{r&!Y{(2t&mF0EM zeP8!=eLnB)^IIe za5!1nMp1pMo(C%{a%?-dD?dr`O5_*(hpOA8gF*yx4(PC1vo z-u2je9q}saAuO`nn=l(jJUa=VsTRmx8CAbgczgQRJgPt3<9l85u~kW0q&_)8!o5s! zeGv?}8UmoQxL_>i^MekJ7O4m9H8TL`vd?YmU~uOHw48WYv(A<5X+6vW4#kPAJuJ(d zEiB)`;FNvd@#0P`KDV++Fao@tEY48|xbvMSlEx3StU|uNPp}VKN(#1$23^qaYM_qc zK6D6jo%8S2TjFh{T8gLiTQU#euu+`uvg{_(!7l>S-zuIL{y5A-%A7j&!S!Lu%6#Mv zE!mA8m)DA*k)zMIts*yCw$_MNFN30x0oYQu=VWL}su?I;!jrZio)79Nc&y`6@xFCh zz@`xKa3&38@OiE*ajf7V&bx4gI>_pLwwD2A~Vqd*lhX8~Q&3nrZg|3KEC+>;7mOKD7;jRNTmiqDi>+XO>9{ zble-v;=}>*aH5uO^eD~%b`4$vF3=l@mBX?>_-Z$zPbnsd0TxdLz)>|V#QEmZ{P$Fo zQ13>`wbP&g_6PL|E`F^D|GQUz5ze)4-At3^1{pe2JqV89XNGG(F>HPL`IaWM!`V_9 zNi`>{5=?I%NSI?#!+Ea6+c!WS32S|foR0sne$?!EQWQUCuGiTJh;dr7EGXQ^H9*xg zw4gF;45NMFxdHN2w2c1#L6ru2K~Z$n2JEU!Z!c^|Dv>_|Ql8|g!sso$(yRdhYlzJX z*64(D#To0H)})xZVNChW4=kV4*@^S1jS+Lxfq?s}Sqy7-RNEUdRo=|vTtVXA6HlML zd06^!B^sT?ASlu3OEHcb^rHP3Zob$Vx!%wkL>y;w+SD6wo(BC^W8XoYl05>iha3i3fb(H&lCikDQa6 zQ+t%99EOntT<~( zdR>1;f8KCp&@843Y^mYH%YbDa=W9Cn1y4S;w+vZ{DdioO6D&@RhZYB4YL);lmVfN| zohTk|#NeokS`Tceb+%8YZMGvX&#G7R8+dn#0QYbHHCsqGG3dUQ|2`;dVF5=Bk z+YncJh)C$KHU}~YH&d9-yxXSAQBClmPDB|NB~T=yTN~Q39!YJ1;@kHW14K4;ebmr8 zCTT&PMTpWN_tiWUP|(QCg??Ajj$s0E!s4?LW*X0=hH?Bv?hMPD9~F@A8V5q_`iBmI zdS?+E)%T>{l7SQ#uDEnxl(2;tWe+fDn^!`ZoYI(f_|tWY#?^3?jJVf|D;Ap+`N4f(5!oCp@Shes&sx+puJHfj!27 zit3HGk~v*mO*3RI^DW&XrhDOo%^cZnZX2IK8?OO4hrd974n_ zWhkZ3rZV3OTDu@xWb_<4BW#>Q;EKz5-(uK86Yd7N_G90%I)NFb`J967ff>o2cz-cy zx0oG1tIWe{3qr_Us;IRgJZG?Co(e6yE>uBk59BN2CiA4Y>F{6U*!=grI zK9n6agA2_2Q0$n#lKS>L$Yf*P^-I8=%uEN(d%Xq|U{(RY|b$X0}mh2w6VUr#@aTFvCLxdQNb!Ox5w+5dw1iFQ3pW z_`1?=v&7OtNazrP8(IRlGgAt-ddi^g3g+QFBG|4E+_Fz*o{WpP*#iC|wzC2@PhWxhXs)+9j=L^ijQM2%6rkp!{AlA+k7svS)V zhBmypa}|E&EN{VgQX-bmiMp%uda|yqKn&32VwBIHZ3smiYG++>kcG7V|@KffnnO zekts^Sp>8bsrziV+GZGG#jLvTAJrR#7XHT^@&1nLX5l4Hr(UlpQEOwTY0NpbU>aY++|8ja25$c|ndQGT%0D75q9ObPQ&| zde(!V5T}j|R`V1#&bc#|Kf1ZCZq{b4uz@#9K)?&kJ~~aU^zkS&vne#M>Al3-mG^SG zvpqs0Av2iyUU6)WoM`XHCm_@eI%%~cJtCyNIMiR_TvaD=|T*u(%(aT_g zV2>+;3kxVx`~#1cprAiNiFe=@X{F*;FA9rbRC`9w?Zr4kJB${tRPhs3G*Hi_&Bzsu z-jlvMQ!GSaMx#^EPVeRkE%yQ(kE|&`=rN*>L?nZkvl>oLy>VqQoEi3Iv5B*0FJXt+ zXr7!XH=rsyeHraiOyr_%0Pe!Zc+ z3%MKK{kruDB!(K8(8d@5lR)Y@JQNYVkd@MA1-*S|Yz8Mb7FqhcC1OSbMq}++RI`hc zA1Bxb8v!C2aB+qMhuj0j?8iptRkWh@PJvjpdT(5$%IZ z94_A&lf^8B(XAg5a7s&GB5mRHH0?No-_GlR%UE;M zXiX^_{DeWMY)~xcRrO^3Lg-H(?RRv*w+yU1kW=nNNVX%mwXKxwHA1tM=#jBC9>}36 zyoUAC-qGL~CIQ|+F!N7%4F|xQlL?5fNG^{7?<*(M5=~b8p@KPlp;ri8q+|)uI|x?C zz>7U<$;`L)PL;*@4%`-9_dYoN=I;tWPBuwE@z}4lGv33-V3+jNrAGM=hIQLH0iKJv zHJ+B(p|(*pfWmRxaj!8z_LgcMdCPe1YeTKsYO~O>2NsgqZod9IieuIC$(3aZ4-{MB zoSv!3)_O1^G!JDdsTtSZk}#uoiNwi5v3#64-2rHcyZLmzY@pIwx$g>dwe4lJQFgvmlB(K!bs*YX+-c<{~A*VRJe`4P8 zieT|6wg0GIx>GsEEzsN}@JN}R_qsAw)UKLX1&f+br`VV!u%gfd5Sw9Nne$@bAs1PP zVc|VxNoGHi!C=)0lR7YL}4^s(=gdvCV zqT5$0A0sxjUZ92gK_Q7khapg;+7b%_58_81GO{{AKl}0|ZWjYoqLg50lCd@```3`0 zW%wtx4><&{|gt$*O9dcfJNx##*VBHzq; z%QtT2L}m~OsN=V7LBB<4`~pxHI@JdI?&@MBd0{MrEgCFNv0VHEhylNXD=FQ+0ya8@ zwr|dU!P+2?!YFLKL(y$Xbr{n)vswTMA!)MBH~Ggst{1X3&~F=+2p)P-y7+jq2lx57 zs1^f-?WBoOd&_tIeKXA2+Jn7T`FL)}F}Cy2Dw(sdBM+ z8sdI9anP%MROjnzL9iH%yXz0Eo-=B3d3~zP@M^T3dsRQ4+7+YCqJtR4Le=l0UkdMv z70jwSu$uG-3&0at&6A!TEghb^Dtv8&%l5b6AWfwl2=`hwaA+WQ;0ql{ZR*^#wpWyh%b4P?@c_MCS$N@=1V9=bo7A8>VXFt`vDt2m^t{zj$=3Dl{C%!@NdW?$z}n=jR}ETXxiMX^ad?g zvSlU*$T~~WkN9iX*6xRRetvccGL9oy&~w*{HmAymgdI5dc=u@*$2rbEH})#lB-h9r zh&AlXZbR$16a;rn9yaH)mYAYNZaN)Tt+wq7rRaYyS_P4|bJ5iDn&r#0R=Vw+KO%dF zmzV9A%K}fnyH@@S?k8rbjLeg}b~bhRu$NgC0o4k98h|OdqE~g*_I%ad-|vV~Ppz(R zR?UKH?R~~~|Ko8Ti5)hhBfOBj)PS)3dh!N!zzn}@hA<)ctkXm(grb*lj6+d1@HesxdyJJ5&mb+;&8V}~>04Z(vHZEN`X z#^;u*MAogOeEaO>T-YXyY~rP|!QCwTU)8>J3M>*91_URSW~)F?sq}4JzhDri_5g^g zocluEZPlzh()W`!(Qj)8XXu-Tm*+r_Gj#VjNx5$S!z}+4i`36^Ewft=hh>QnS@kOq z_SuFH_9lu~xn7%lxnm(mx(`g5meABsa8$nUy&~x}joUwhH#$Msf-*z9Sr~lf!YVnj=v{cZOx#X+^_F#^AxQ zJl}?3?A+_Qt2NDdqYo^lM0oxCguv_&MI*+TXIl0yT=2@h*_S$AlVMJy_*6bV-m)}- zb>&_A%|iX(%6)EqTrcV^wSg7RD!W(GR==zjUZ0NY`RMychV4{r;uY69c`RF;N3e7) zKr`;w@~;WZnf4Mo_Gzcj)DCrn$a1&Jy|Z{6hNCYc4eY^kb40$EhESDZ^oinSl<}c> zar&{M*H^377M$1?1o~4pWap>`59aj>r_Pz!mCRv*xoP3DG z@2t68oC%hOToW2=`2GE6dv}A-L2WjAIwfYQNoS~d<}T$e3{XPrY_P~#lw%!5%_v|T z!CR~a^O z8Hv&H#%8Y*gn&~~3SYC1t`!Z_JJIjp+(`%_a{KP2Vq8PrK#qqLQ{R$vpb$;P1Mwi(b-xnmCSRk7YvYYoi4Vr{7z+_EgVmBY5{_ zU8W{>EF2lR((Xe3V$Uq|3!>C%RsB(UCy2f3(LT3}sKtdE;kESjPUTLX%-|cVW}mNV zb1D3c*Ri{MfVWU{daB=Dj(0EYCDuV~NtkKMW?9Y{*9P_9+FG{W-aAw$%phsGyk`RI zKp6iRM{GPaTWc@0CuBo4ZtUD(VKqDk*KMhp!@ek+ab+ zvm-5ovu1ecDmy_4qh34{P0bCI+2xr2fcEP&!_fNmG_`%aKk$)tk{wrfwMClzUQOG~ z;Uap?JsOZ-q%`hmb={CZFrV(l0x7S?Ov`ZVx8Xngd*+s1y>W5eQvuOKIK^=|s-<>e zqOLdh6o)6B3h|n_j;OQ(O_|oV($hugFhtv9>|_Wjnei< zLdO;@4P1NHYD^|n>_?-Po|7$IjFLjDN1bx&sI)t6wNZ1o;>cQnWg$oAjp&6-s*dwBYY}IwAU7#MY^Fk zBu_Hm=|Ic7bgvC=oHw(sY*D$8RxC_ctm&1w=_apruF6541tO5&CN3_rfovIE}j z1F6h6>~;Z*D$9WM=J?*$2SUcQ?{Vh*T`_rU>zB5d`tRI!I9e$yoH4xqc3Glf79Q46 z(|84vc)}jtHm9E-dlJ@bpH)x|=-&yS=~+FS95YxUyA^lZ!l zf5|4f33BME?6_d@hqv?`f(1}OO>t-5%&GS9&t=D;2f#`k!MuaT=xpRE?Hn)Ng1&3m z_hzF96QQ)oE^Kf_6SjPTQD`qZz^Du)Ka9J&!0r)&yTkNM3fFYj9Po#5a+5XEZNkT% zd;FO$gaL$6b2IteziqD}7VfxU=$4KW%lT?N*Nkz#&b|4Es-7pf@!woG#xu2K9!2=Q z#r#;KMNkp9SL1p&?YCLJnOZ!gsOwHMO6Z-){xar`hox2{OT7DGkDPTvOlQ@7hy$2+ zt=I5+^Q2_1S$HY)Ep=JhBK>nw4Wkj?`(5auo_)dIi}<5gozy}3T&x3GYZ=m+I)w3u z=Us;&*A(~1e=^RT*&!xZD4mk3-$^>ra@WBvAJU*Le%CAFE7=HS}sPo(l?yN zHJG(eA}y87gA|J0-}xP7Ik&GIf2z7h|!??9X84}Llrvdszc6b?7Dd{gu zUN*TV9?wtRpAIRx-leT$T0FOB%V(~{$+vV)eao1(JDq(X{Ut7ZkH7kJfN9$T@I_Ha z<-QaT;hU##$KLk1;p^+S@d7gKAZylj%$HCFO#Oaceckp}8s;fc#o7;gO{%g_Tupeb zX3!Bj$-u7#tm)Ns2sXhPaRKo0cj8v1_w(3@V4eHHRyPV-A5vo!>VVKKs&j~wU!ak^ zIyzw_Js-E~kVbK=lVtsP^y1XvQ}pGB?LuJl8WmNtxRg{+}WvlQvQK*J+(O8uH+1F2sIu(8ops~5p^S^$JY z`JzS;iQ7)f5>3|PfXV??^4kZsQo~Nd=9POt^HIn>J@A1;A8)@Gc3WM0oOakP)#uhv z%N7ffuZEWa)qud2OHs?v-{nvD3>-ubKWPYFp)vVofIw8@=QYIDoQB?t)5%E2Y#y1P z2LQen5YcGywS(zLPLWVuf>_!*TnvWn`JHb)5~-6gL^2I@7?B|1_ga$040R_r&fB{PW@=ZH5*c(tBOUY zrGFlH31YJ6sT`8))O%wV-F1)YnN`)^UlJ{iygqLcz3`p`EnFvjrV-7<4Y8Td@OK6? z&{cJ=Grk#(QF<(8$R%SSX>-f&psY6-8O+GR37v9~krUBm+cPPJ*c8idura9)Ti#X& z`<&BCFT9E<{W< z@?r0?eR`~zB70n%a95l}&_F6G6{9bXKR`iz?%i@^FF5g6_O=DbEZun+PPh29I>lZg z>!iVEE0~bQH~gtd!W5KMs}CshPm)s3?q=0324|CvPLr~a_VB;JTJp@!^>iI#Vaf}i zKTYm5-RtkXb@2tmX5v_9E!hF2gRqKOUA~I{! zzVoE!FnCVNL=FwXtVhe}nQf!hG{p$UpxnY7B$c~PKu^w_&>B0%EFFU464 z8ObDsBX9r!#FH>A!LfE%c@nx z{8&@sokuu!=T-tEM^;|#0?3OhtG%^i0_&pUxFV}t9}g2D!_~_@7c^2X2EN@b!o>BKB{3_usBh&x!khW&KsxYDN+$0C)qqNB4$zi-sKY}4Q?cY8VMa&5#P+i#tb6@O?2LrIE^~hmD#`n6JXZaViKeRrg zFIOu(58GAaO%W)X>$Zf)_~J9Fi06`s)h`#)_YH=ATaVmefosbP9YhUEXhBQn#)`|& zo!v+s?kRrR5FboaQV&CszXbmb>o0+apeiCg*u`#+n+$SSFD&j`H$V5Zz3IF%Uuy5L9l>j4=YWqb1aV7=cUfY^(#EPMC#| zqJ-*(?_t^8JV~-AX-!DGa@V!ayNHeRZJA~if}ui>%4h9uz=TQ62*Cxr50j(5YERLR zxuTBO3TneGO-n(tYamo^WuRoaSV=@d3N*p-k1eceuKJ^tF&mLGadB0qJj`9ZhDXom!L1go=;;R{?{1?fxAE6Z>j5`=wDNuPa7%8d^oUUi;f!j`ZMecM=Utfy2D5iR{5k3(= zTtov$*mF5dAJBm5jE?y6KKX=J!(3}dPCWn|jHIK`mTkBdQ=XeKJXin^5@9B}hHI=2 zuxxTq{rk>uK9SUUc*!X{8eiI(OPtKay`1@QUnMlBx^Wr|LnQBn4o3n{A1hpEvIdYL zbX%yboa>ZRPIc5g3XUl?VCi|(keJY17w-FaR~%vilxZ@$Ud&G`WET-!{9uFbRrL&c889gKCO#v)Y%Z}b7#n7A z5|V?U=IXhWcj2yyhOfXw&kmIcEx=>}34*;a4jU1~DqT~oa8 z(ZR56%Cd!OAS@en5qOV0AJ>UAF3Fm5>C+Ed0b0wgY+*cMyP%Hwz)=jixOrB>dDjIs zCHQ!Tt=@v`Z{NN=r`62tWCF@ggl{tpU@-Y@2_5~*KoK0WYMJnq!xWFF`{2yBMO#Ab zyOU*E)^W&I@_sh_HDygtn{Pv^@@fJ5GOUk)EVFyG^;;&%H^~u*Q%4V7{(L_z@&jW| zgU3*bY{$mNPbx9r_eqs9w2=CrV1q#=Zhz33nqZR!D$(px+l=58 zP{uMk-uG>tch&LQ;+tsZ!JK^|yoa937DsT_PK8#7Mn_kpbze2{HZMn>nAl-D_7#4t zT_cdW!24e9EpTni-oxS|1%nB&WOSCTW*)Cx_z*OmK=$^JJs`s0IWKEbfzq4x4g~K8 z%GY?mhrOlJqYgY<9om^XYYq3180X-@^03eN86-T;!f5Y8JWL55-k&j?<%v!7Rkol7P{%3 zI7#jDJpE1^Vjq3u`D`tXV*1a4mv*ad{I@c|U0Et!z5S#^?_mW z;t-&t1Xp?c%?16NZlWDGq&=PH`Gt5d%>G2LbrGPr=M6Vsc57Z9fgIK3U$dI60i3+| zjIqW#@%-~kBcT zsuM@{c|QFGEb=(C2nE;~SnKoMJ_g^GOfwMwg<1e}jT=~vI#!M%U_Qo@YGE$0~N>J#9cRk?|q6Ic> zQi)NnUTpx9{qzf22?cy0ODL=5*6?h}zP6W=sAy4twjLvBI5jWz7`IZlMv=|$#6xCZ zacVeAIy51vNumOvK(SWz`}@x^{T9R{eM_;e*J=mV@LW&gU?j2EziR*j8xM&pg^-u) zxk_wJW>)>kCUUEpkxY(N;H#)#3;Cr#JM82{Z3hydSeo zsxlT&Rkq*3EH7{r?{)R|0-Jsb2xZdkajsXl%Wp`GSrHEk7dY7zs~EsdD5khmx;Veg zN-RUZ#yes?x(OHg*RxC2HqHv>PEHYP=|)pai1uH_Q6opi(XBhhKJ`eqyG#M9IgxE_ zi5WB=pt6n{d_>gM6%Y}VeGMQ%;2Y+nd6d29O0J9R0HC3*Xb4zAO8J^S3 zWVgBca^wIa#j&8jBkE!L#GL^Ar|ri)6YQYX?H=&{-jA(=Lv4kjDbTV{YD59It(OGR z61@<;0{VQ|UCdN7LCyoU{MGA7)6@O{P&}{+nOe)g0SJqD7mjl4rF$sX4DbVYp1|3s z07yXQ>|l9lz%VV3_S#O5YmA{P?gi4KL&3G`?ANi$Xsjbr-4KR{8RvS6*5+P4b+4xo8(4YqhLz{{{6UouEl%g2 zN#-~uX1;!1J_Psbx%BoHl?b-Ut#4%@qRMnpAT?M3(OK{=2l9_Dl!sIlVj5P!#cSCi zriYFLh2ZfAqC8Nd6M)AZw&;51p_&&^`mMK2F$bFWR5Ry`El!)*uc?Ui@G6_j`GnkjC?WkJ z(}jOxA4D-bu<0%NIttv;zRGGvlhfy&!}UXK>n^uzuAiE@Dl{kD9JCRRF)2rUVmE~w$|+Tjxs@Y2c}NSns>YkHdc>hk^Ws80e*Bj{ zxiL%=I)O)SYwq?AlidVRQMD`PO9iO5!#F|}Ko~04XkxxFL|R<$udw|%k2()jd4=N< z$zXss}IC6M_acJqcj}Qa~IY)`eR#2ZjF|jewB18 ztop~+DtpU?y;EFOeCr`MLJ7#V<)6q68_n-$Ec_S^ZGU?0e6}?6n+Z}*rT|4;U1sR* zXMHlx8VrXEMQV;O8s=euL{;|{h=w8JTASF zu5+rPZh3d-;6Mh!7mWg`F&qdbovKfmaNTil&~=DYeV%$Y!MZ-1U$VTTIl3y>^YcWhnrD3;xcggT}+o$)ChzRoVWp7o$Do`yyb(z zRBsI)4j?<~Qynvf5c_wrn|V~RR@L_zV-jVZflO}f&zUwHn%L<2*VV??%9f|=*aYq4 z;GFv2C;`AC^z6At`tLvQiB1qdP2;a!TAxyPFZ(nT#(-_&uT-E)5JhfXU|CH9r&WIJgD3m$GrxEs8Z~1~ zfM934Agvgjd}sEuoUh}|j%K0wCa9TKV|D;KNDER)#ev0xOi2X7g}SzUp~a%UJ5v*` zh`taLB~G-27W8o*3NSg$Mu=^68yAApoDrt=iTCaOR~2Y|`OS8Ll&tX6_re3@F`j+E zNUjSUGPu^k9icz7_

EREV|894ejHG@)Br%1RkNSTtRZUVElJ44SAUf|d-e76Zn5 zvw5i)usT5K!F+#BKdQOSEeM>?b^vW)X@lqgK>20G`|ajl

Sa53Sp%#*qqKD@>N6 z_%!^!Q{7A110;&txbnnf}iJ2aMvmw`kFVz0lW}|6$J#}Z z1%$^p+CvWAvtT&~O9Rj-x1rgs9j7rqZLcO)OF%#;Y4GRrCbUx2mki@}ph)+{)e6BH zpna)L1`$c}Cqw5ZvJL#6AOr(!rJWNNG!C@A7fc@ktx7s2w88A%c=9?6BmmJ_k#p4X zZCKllY9G0k)xhcq8>H4Uae#FXTougTm&561Z&Z8nLrC{IlRW{FwyGs_OIO}rCKb4<%h0eX1`Yn zg;|xy2q`bhyAno#pjqLrSPptnD=%e5DnJgdYyM+GHF=#D-zVxYh3kTYD-^2}1)!J= zNz>_%G>y=82*z}`8Z)^TcOed>m~J~`ro|^dl3y#p(1rVBzE>DU{J2T?w-HZ9#|>Qj z%|vkv@r%7x(DtloS|_aLfXk0S zbD`BM?VdoO?0rb{yx*0<0S(q$yqxA*_dMFM4tf;3T7fzwFCVtNX|%|t{jt7#Hb(H` z&;6kKNibB0Oy2M^+R@`6l=mb~cG2P}Qi8gXVtWu*JJ4ETm8S0jOjc(S?l_;+&*^P8 zcb96*OC=Az+q46&9(n{!g1L%2h=J@$!l3{s%CYT!hM((KScfv#0%3iC#=mKVv1O=5_^g@XWL%U2wGwryYz_>860AdKV%yFf}%lYT|uNF-@ zV4aq@njhyM#3sa_`K$j0EAMPkIzscC_Xp){s`=DNZoeo)x9YY-v6@^LcxN4$~Um=EPUNkxP4lX;>_UT z+z$mSNB?uVoX?MT#YxrD{B)Hvf8pHdd3~n7_m^?+-MM{`e1TZA$)c32<5=`eajG}@+~8Ayx@VtGn22(39-k>PbKSy%)qNjnrbuSdmkV%Z zkUF2Lqd57uv-+=B$-(uUN?wQ`95(+`En&}r)I^k<;pCHRHvS2z*D#=Q)}|h^m;9CH zfIO7kUa>kFuIE}+08GNQ-PhBI)`T`uuQRl|-aV(bt(bCpcFEPp8u?2ET|8NgBdcf3Qi0@!Yw>4!>Xa*OO;~LOg zY7jeqZQ$E}e`I&9Y$E-xxC;n9DRTs~fSv>oNtP7Hurp?V_5K7sN74#B&hCp!e!*X4 zrM$wMlI-9?KU8!ye1Q2s`L|flL_2Y4{VDXkV(qm~BniiH2doF*LZ~?ywSB%JfMAVUEXTd)djC=3zEr0Go^tLO;Uj$Y@_U$`cvAr-& z;9vqFd@dVH4fxOWRKai7E?t=IIdCs35!@@9k`DN91WF))xh&H!P~Z?Y9JR)J2`rl9@CA5aWUe zwX^VYop2EzMVhWTwcsC^O1?ABUZpV7>*-P1h+3aL*@&D=sgopAu-+r#gpnpKHla5* zM$aOR_`BDq)b50V?@A(@HunhzZ+*1qW3%>wlo%y-ezDi3B7^O`59bXbdKmoXu9+=* zS3YE&P5YEOWsYcVk}QvKD92L(NL-x|h-kYgyT5P5PoDvVsealUUWHalni9nRg1m4m z1?^hTUfKu{+VN6jSl%tdS0PN?ewMRh_9m}l*OtJOY;XWim>Q6B@f*EM7^>#FKmitF zqCncT8weU}f(y?F%4oAj9;aRc`_)(h2YK^w>pcAetd$(tSC*sbdU7za`<*?dzeB;L z>A7o}FR(avz#P_T@K=JE2T^!;OSq z7gv8$r=r-}Djcl9+hB@@3&6gxz!+DGeuy!usfS=O;DIZ&&eaSU`pVZ5xHSqhcsto6 z)81+VMDfPehc2?3trUa#~8cFl}6>WH1ZZR*l0lsSAq${e!acDep!s!{h9 z-8W7{IJ63xIAPdz+46ClwDH`h-BUJe?_C+@k`DA&={}#v6GGakdmaXYnuaxbx$|&}6+yzYjC! zo*>aO40&`Mg*8;H@;KhIwG}&NTRoM8h-=bBnRIUAb0t^pQFCe8K&cP=@aCmZZM+`@ zMw}j|o``{WPhm9Zz@tasa2`FS@&NPzDsN#QsYoSPmXlPCPJcr=)njRMgUVOyh{Ws0 zV{H6Dq6b~(HZ>KDXq9g-1Z(!PB2N}3=Xh`^BBf2*}=ulT^U|4Gzc zypJt|vT?+h=Q~-=qX(BRx5IQ! zO|*I|Io3uYiZA1fM*n!+0w6fUDW4;jv-<9}H(;oIk5J~;uJFUqJT$5O}Z00YBwz2go)w9y&p3kv*wHtWo_=+%)l#}$HXpB)@t%+!`~ z8ZR1Jxh0vzRaHgcX#1xJke$2V^%gspr}q|{KG#kquI}$*_!O^^{|lu0-c0>2TwV%v z!Ub4rU*4Hgd$~H-vGh`#!WgE_lor`w2@OTG&+y*fa5`+iRojhxb(#VDY22_-<$);l z?RJ5}`zFZ)4`onhCGevL@xfT{&)jyvyim%_!46}#y#^y%l)M(2n7(Tak!W@bi`R(^ zVT0Tz+^RTxD@hOU-70xBtqKAx5Pk$|sRMI%VWzDx_JGbG#XQi>##RAOHL&~0L!J`r zN^JxQrH;_VyJCNbZ#-4Me*^XEpMbH^Y*boVUX-+#cVMp52{r*|QCZb>Sf+d{>-F=kPdA7F+?-FjNTCE7+Lv4D7M02t7?J_Xtp1~yo3j$$6Tu9O1 zLeOT>zE&|b%~;O2`3ckhki3l^*|It%#ZH!tfttt}?F}M?rbQjH=0v2@Uf+%eGaP?I zNBQFV$wj;!{WVb7@^#z@B;jQSKS8Yax?^{5lqP=kyQ_>}3?!}%Cs%~m8eYbOlpbk~ zbQ_RV(#6m#5PW8;)*{Q_3g6LrL;~V0DO919TC1U4F}SpOFc^x& zj|Z-TchC4ac+3spu9fGyt#xMhdf3ESs2PAjl0*tdZbji+Z=j9%`JpQxd0bFj=qkxS z({ZE0=?hiDgk<{lJFbd={cEc|09a1VKWQKt8B1W-PJwObqk2-$V~O{vSNpTtoqKL= zJ$OT7&4sm;puG?rNKBAhOm|r7vem1momJ2!1`T3{9XR1|hl^d!M!$YJqtL5D=IUb;qSOujw*<^=R^#hI z$UShnNf`Z(_aZj}f4wW*;Sw$Z<&1S5m2V33kkk~UP-$nz2Wly9>ed#E2$s}_2zXH4 zSM(WBodqzeJ^`AY(-(rJz8)?4}v?aT*}*Tf>ht)oXz&SUF*2GEEEMy485Q1}Z(# zgXa%i*dqj3cpYH^m5Vl@Kx6AP>6~j-zY;M)U}k3zzSp6?)Ds^;6q)~!7U#TN&U9O` z#2{j)noPG*rp+p18|v%(bs}>z4VcduIVThE&`X>w$w}6r(%jpz^R_73BV(t|lak|A zpt7aRa9KIxalv^(^nmccKZ?gN#^CJl!P)mIYehe2oLF2XD^GH=@>hKG2nxGV0Dt7V zy0AB8ai+M}o-~pNB-~QFy7Wez1$MB16QSjPcO_tk1$%Y1!jE2sv+&3tqb(dz)!^HJ zIY?dD=X>g3ttf!s|3+Ec{ObSnn-2w)u!*mWE846W9-bZmCIN*5(Ehqx&YRo+!cJsP zNv+n*^thF(L$=61Kwd&tLgscW6N941qeJOh6~{tp@=DoM)?^RX2h7~KrMNk&>h=xN z##L)i|AQX4ao_R{)o7u~TPqql_*YM3eZs9=;8{$sc{-|nt>^r6UG6vSt6wIK1Odex zqSb^iNK;GG2T&8EjMTd8H?-ZTUn55kUjtbgC1CzzVC?ZvPY&T^*CICM@VZU95tAxgG0w51oc{@sm9V@25MBJ8aFscGaK=cJa3Udz z0W^{5VQ9W;T4PDHoPulXM;=gw@A^(F>6Wq0IHnEshT9v_jgqrKe)u=8S!QQWNuQ|P zB2Bwa1H>#g)}7ZY1&iBldH246ku}gn&|G(a3f~6?Mw5>irx|z{r~$3rmtQ;!xLW38-55q|fO%5}iky!GF1 zv-RvhK4Lvk68=lKv?do^;GaJ%tt9^S9RL4I{Hv^9BkC)p2_fI;)Iv8EQeerjx7_EAu0_y{HL?T=7(BC(P ze=Y537maz52SBCOH|{yv%V7pp)A)x7P( zwUy;MsRh-E80iCS@DG9S=Hu2NtDjjuqJF5m`1MwZyc=+pVvi4zo4>fAdU+rb>E9*S zKVPuh#c!`uxsN^xgFp8eAr=BND8m-0BZw#%qdew8J!DnHh!A~bK~~uB4~0J5nD7b|rp+AGw7}hj)J9#|-^H?VV{< zlV=)+5sQk5%ao;ximk2MB2dQ~kS$t^R;}WK><}#?Y6wA*H3TY1T~MN^pg@RfxTG>7vL=SYN_*Wm^Pmtq(VWE};+d1<&4YbBh{H+D-mhJc$tjZB45Ulf zkHwX{+`OanoU>Hv9Kf;=zVrchBdPo)@h)!t1Q~}`p^estkZt?wyj!u)f8qrxd`%n+ z%6uZeVVd$(H+32~i^ntdiCG0*b5b!FQZkL}KQA@CzWuS;8{t?#o_?_QYXU0d^LoS3 z32H41p}b$jknR*T#k`!gc;K>h;*B#>AsW8LqF9F}3?puqferc$m9IW4)lT&WEXif~ zz+NhNm;5~I*44r=Hi;ijzOe!973P8i7Q*A%Lkq1}GH|cYUkz?)EN-iF&5q_RqKl;l zd?I%2Y&%Lz+2Sk-qJ}z^4`dO>X&mNE-e4V)d)lyXriTgHxfc}@GYttkI$0{QRHd(* zojP{O@d!L=G5!kmCX$^$qR`d{Q?wTk2cEZ{_59VA5Utx0HslM}@+;{SB}FpyK0b9c91C@edCM;IK}poT_GgCrSJ6rTnld*L9~_bN{VkW; z*9Sw&-{xko&S(`|9&so{5J+MB@ta`y@HHYM{!1{i2iYpJTcZTFLPQ`lPVziCaBA+X z@sd?CV_Ataly85xy(&0&<=z{mSnRJUj|T^D_yFrA@tTpxHF|_YpACp0e^fM+Q>{ln zaDv4vDUCkO-DYnphuTQk&)rQ6QaT>{`J={*^a&meOs4A=Bp%1Gl|*JX$(ZVCK!Zk$ zvoH)tdl*Y*q!jnx7suv3V8I)23dR}#DANZ7o;1WQJ($Q}O>BIMSu#?5h|O_B3=TN) zSvgh62+Qqi;_J#wo_dNr1N#C)=F+sE31+z6F5XA#co_JGzhsP5Y%QBv}N;#OK? zyD*NzRQcw<#P<~1c#|?44^}^M1oQsuVuYibQITKQ*x)=%-76M&pre*#I-wVN{Ma9` z&B*fDO>A+x7J(9OMzXzRcKK?KOBJML_`W#a9fAu3idGywQX?I6D;R60q=N*?*Qksk z-7a`SOKI!&7J3a@{hKpbLlg9@KmIGYW%KTn;*{LsMYb)biP?GVUwwf%MF>=oGYiFM zSzB#o=0(qUXHyU)HtFGI1kG(N5YLB8PqbjZv=+s;pt-LztUZ_%?hb1gW`(yOK&Y@Q z$Ut1z(fJz+N5{@z#|^m!)3}XRZne`o5o^5vwDtkf$U|~^SkgwP>|+EA2zQwUS)2}i zVY#17^*sM?lyE=ZN|dYW5+#;Cgl5%J#W4?~4?2R$x#G;vyq)8mY?;t)Zu5h9Jt;Tf_PT)o1UD#IN0*hGYl=peOY*luk^S+Ie(T!zqb!wbMRrTh-gYrMW~d9G z-y%o|S-QOG^smgO@q@VV3q^YKGKvlkqxXl!T`2&cg&RFpOQNur6|4r?<&piOWsDP+ ztSBvAwaE~LZ z5b}PeR11UN=rL7IOe&Zh6|Hdl4ZvohroGF*5aElyTUf~bbYVf8geITSydVWaWNXyj z=|U?oFnS}E%nS!F$@gkQ6Lyg_bHcFGGFHgN!(8pB_Bo^wTNXRi(aFA%vzHP|n3};+ zgUGHyxIQzj7X$tHlQ?0CXr6%6Np^1*i{g;Qi9`L zr{Jn90uy_(M5}?c!F5dpu8B9);(3dxg-lrq=bcGdezu$x+7TJMNY_04r;r(XrmBLB z#%t_EsZ}Q(XZbb*+qrk7`dngWUz}54?D5u8(JaHe;$xn^&AZp;1h>pZ`A;Yxbaqkg zi$Bk`eOfcGg04{2xOD8f%Fox@cBL>;aJp1#6)dl1xw4K0Qa4wjPz1roY)IVcGIM+e z#7g5GY8&A5lzhM%Tw#r-RAjt9aNoBNgyFBytvA({A?2cG&sHxi8y0eqIeXiOZRq<_ zb=kRCkdnO6Da;$}BhP+oykcyPFBgQ5Edku2eS1@?5KwdlBsD1NytAg)Mi~cF>LCY? zhskkiN&AuV0`%1`O=Xh!yCBnFkcBD1uRHUtc35-E9~%c8n8+<;waG}4`EEO`+7O5y z@uU_`0IK5;@6I81Z*c*_eM+;vgW|{b*c@aV(T`2nPQI$P=djHhWDvf+Gy6$nkv(_>a?UG9{nPDrLUB<t z&)qV^l1{ef%0J_cb~uPgx)S$$$8m%&_buYVbZ*Aa6PBJ9Kt4jNZ^L3v_>VD~7kEJT zsa1z8E&|OZ?gdE{DNWr6L*Qu_Z1}z@`YVs^Uy$9$%1Zn)hk%Kt_5X(8jUP`?zpOGa z&Vu?|65Py|g#43~D@!hFsc+WdRtSq1L1Pmsu|uWCS^1 z>X7mqLILmaDzIg+4h<$MA5pyxA-Re#Y^eYwY@W^AYo=`{zN`uS z`Yxtoc)8I!lK{ylORPDxp%Ss|AdFa1T2-o<#yj*w$(hl$N0x0`JKk(QHzG1c=J7NT zQSyyGxeHla2n%R2fH93|8s@8Q8S1N3wLu&7;+DuvcA4+ZNYf9`kH$8q6ZMW_yCVT% z|9P>|wvJ#(W#y7Xgjno6m5Ia-gecd(W|8S}uZmk{_oIMiM`kU5yPer4gPwLbr24TcXNG5804chP@ z)LBcST-)EsBC0AjAnN8=IGlzHEFGG9w@MU!-dUzW%9Ygcs#XYgTw_t!vBYr7_TtRX zAj6r?&W=3+(HgJ~0rZ%;dBhC29UcKo!^^fv4Zi<#XSM09(N0^yE12QW(!Yhk9D(C4vnXq#6quK`xr1}pQsm2ym607gL`69^W5 z3$iJ8zGZV&)*g4dhZfGKt^`4vCRfWQ*I#z84rZW_^g9vSJ8C`Vh2f1G+sz^7Amtc3 zSf*?bCTXe-JWoUTl+fFAhC}JWxMUOUVcM)*&2TO8OFCpr6+(#sw)?VO#!R;xDA+Jja>Q7csAfliB@Es z?F8|>svDdENF|l^>`)P8nwC~5drzaWQl|gr@$$!eU0~Yv>x{KOR0XtO6h!*v7Ds|X zgD)WrsX6QHM*Yk<>L{f0N4oi6$J|DoIO)~Lf+Pt`G9~OpPbs7{vqE=Vea&a}bi3z3$>fhBAmqJ# z+}2pN$QwPBKw2D-U=jjd?lSfGI7VXBx zFJ&{9pU5$gv7;aKUdr1L#UH-_77qucA6ZkWN?V@En@+lYPG5#Enz`4`KV}6Pvn!2HMQ1Rl1**m5a{1Uqtac^Kp=i+vrjvtZDM}g_@0eVxEER&07EU3S2w4$(Xr+V5UDtntpv4!4dK{QHhCiTcgf4 zXd^;GzFZYBOz#PUDCx%oI&-phNnQicLg1d~uybQC%`kg4u=LcXDTYdo|7gK)Ycf|~ zYBg3^sBS@TZ;inMg0EX@axH6MpiyO`%G_S8`#);-8)EB4(4ZUPx9J> zP(xsZIZ)-X4BT?R+XW|=Y`*k`83KO15mKeeDu_!qoCrFq5a+SD$|14omfSKFHb>839C9~hW<9F}rv#r#nns2~Tx zltw{7BQFLTwo-+AEBGo%#(x2Uy9-baT9c~Hj!!gnzk+qaO#jP>!#!e*Foz{56^ z3)%ky?~eGh^)e{#0P69jm8mm=sg+v(D-lagL<-ISxd9sNc;3L5n8S7 zaS2GDPi1=-m{t-e=i2rvgl!;2Zlb!&r%juF(&QP9qhW-Gz0jJS_H1EL5WD^Rc~oQM zzWg%UPu!2kiSzNlWEXS}sw*Su3E;|q1RDxWz8D%CqG8`Dgj|^vHZ{Jq{69P>?-T9e z?N{>v9hKe(0N|aZs-e+}edJiF`T^>i4TIY*2Cz<)oO8+u_sn(@@B96T2j7(M5p2G& zH1KoVTVH_u{_Zf!tySm#_}qQu{QCvX{L{BaMP&hM>H@0gu35{%8y2;t2K@PF{*PeW z9<5Uvw_4b+QI7p?y+3{IT^Gpq{`srjj#q%N`qNSHqyMi1_gz=1FZyVDFML$sh}?j! N_B(&b{eFM+KLDs&8HoS@ diff --git a/doc/wiki/gfx/general_application.png b/doc/wiki/gfx/general_application.png deleted file mode 100644 index 661610155ed2ff534075b16dd39797aa2dec2582..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 147288 zcmd43bzD??`vt1BfP^SW4x!SZQqtYh-6+!19m9wqsKn4nE8R#7l1g_YIdsR+F*D5F z=sD+o-`_od-M{Ys%t$%2_x{H7tY@wD%m;N<`P=wZ_&09cxUHxlqj}>7HvGm7j5~NZ zz;A*`_nd(*H{CSlrEZiC&};%fU|CD5NZz)jQa?Y3|v9CwZ6JUzs{sV!J~9E)2)9$VhKpk@BHiW=sqL- z;e&rWoPg6IG5 zH$+DG|K)}lAHq2u>@}n(YsRuICrrMenUe`TTrbm zElF~RM1^XMiO0=;PT*pjlr<1GRDIh)EFe14_&kFi@9jU2sP~(*_FwV*$?))yfpdn# zgYs7RZ=>Ekt9T`|L*O4?x`YKjwZ8M8a{}-DM08FrtVJO3O$%uJd)lGA0VAFi#?nsi zEk-!@Ki4Kn5{!Q4y~oNqwMXV~iY-1?`w#=hD}~iW?=LKd!~LjvRl3W%`?C#ch2w)p z0^=5k4=oh`eU|Y1A}(CaWXAAu0pTPmX;U_uY+uIWwC9D3#V;%Y5FD)-tJ==#(f-#vu z+@=k{68f)ErAKx~6Ab1LzAx~7O+&3-VpwgnHCE8qm&CIm! z-D$RV86Dw%wK&>eCB&$N-1DzQ>g^}FF3%6L_NXZXfcyQQkoHyHlreymp<#rp@W?C>NX=@(av43gCsdATrW^gd>?VpS8zE@Zvj{?Q;Lq20 zNU|R+f_iS9?yr5`hMp+Q!rm%E*g6P2IKH2cKB>~2KUl7JN_9Cu zKmY5l860l~90%&|-1_{1U;@&bjZJNHIpR?DI*;4O3}xa5aXwrlFsxsG5OJul)EJ_Y zJO48;3b8X@zCj3+$tB`*gc)Fr-u#!Ogd0fJ`05I?=3S(2^wQq892@g3R;Eafe? zmOk8o#c357|9YG(hQ&QGyKnSX65IMae%uoiJJ)>On0aiDpUikD#E*4rW{7`C5UJ$2toXce&Lh{z&l$ z#;@*bQHP_t+%dFT2x1N_jgs?GzxvV6VsLoZSiqoSrRPfgaPY0H@(8?uVDmT#@=YxG zuWOCdbJD5hnx2xe!519clZ`S3Y2;5hQ5;Wz5W&Tjx1lh z;0~>rzrJ++x9pJP^woCRyv2h84ER~8{kXQ{hh zQqIIYP*k#HPtgKTo@$rb8nJ0+au9%T95k>m5ba~SL>inHK$LnB@kK8sO>iT!0++2c zib@^hc)S9*)KbJSOMWd6B6g0y%lhEoU91_x?K2ELSB>STP1LC^pePOXb9DKKqG{!K_3slT5V?vCXFF#n8Wkdgi+?EukbZYWED) zIp1!2zJV93=qsYeP%U5}zYQ#WIPwji@(1jje#adBPL79c+Eqd7qYGvr&>b zUp6m5gpB%SgGMh`suu0VSW4CI0K&2_HQqX|NKK^=zt$ zMJr(k`Jkmw$M4&1nxAz#dXBi6-l*uK%gMXsIt$iasqaQ|2fH?HYP`*cokEe^X5()) z^AvkKCFj0kzz{wAsdsF)miki-ZMr={=>>GU`O9b0>j96rErs*w4J#rhKw_Ofi{nBs zu&+MYLx!fM8F+mb}D&mCk?{zlX@Py&)g<8Wr;_U!vvpX92 z_Id2(ol(~EA{*VUwpBl~aIs5idUj3bo<`Q1O!IaqEH#Vph0eePvv5mjVbQ09n<|sF zbw{JvcC_(kkpuJqy0H0~Jy2z-q$f6S534g9Ba`y+vE!Q3*Udwm?Qb^)Mic)PE@cR$ z1JPRb$L`1;C$lkwhVhi6>MYfnbm?z|cLW^j35|7U>T=dz7TXkQUlbbSRspoPHxuh6Gf z-5n@-v}U$~Vtl`YkGVwrxsA9^a>g_8$o;|9OVpFffT~VSHtpiL3Wz4%CrROg_hbPm57A)MQ2rDV) zOQh&ZN-|ANl?DxZ4}Tg^HBR7`eNYj3H?pyfaSFm=ft?k*a)^BT zUFAUrvXc`lj+xd>@4mi!98iq}9;ch8=k8Qig&-ki=2Da`FO!If=lOglka%6F;|phG zydyI4kuP(4-ID26JVV`ek1Efo_&->F1J8B5TK*NaU5J5RiJ;IP?S5BlAvw9IMZsgI z1R_AxUwYPD8f*0sxXmqDvT4FJMhm1fNE^f?VzRsQ6;mAjmtV8MpV+9^XHxPx&P8Y; zvK1&VoAk$BN5Y&q1ECquR1a5J3lzFtUs;*NCfDprKJ3w1bL~12`n znxLtRr}k1yu5%R_&z}k2)-ATmGIRF)75C2HpHQfH{tWiEE(L0~CVBt3>_wRBikNlv zp%}*!A09k_aV};s0zGo4dYdm8k*epD@z^;l;Wt`^J4|^WGp=^)z3JmD=^mL*C`{I2 z;^E<`sIIo`N#N{drDr7jJ3!&C9e?31(1i23MD}gw=Y??&suCOWq~_GH?dfDP!ppfI z2=!>@JeSkG_fee;@o}tu>f_-nf_o=Pqv$rCrQwc<-DSZ}(Vn8XJ~bb=SDDFH5B1lY zPcq6_;h|M-ue!~isp%#^`OI39GV~#&x~$(ea3n`jkve|zZGec_z!Vm1GVRMu@`Lff(6cCjfhN@lV;{N$5H#F%qe`9wILo1s<7n};k!}>73)i`2wxR%67x_PXHPUU=!^pMzJg>hKR@mFHcXcLsgi}D9au&0 zjd=>5U9U^nM04n9L(O4k>&AX&f2ZI((#wV^#M6jVV>to=YH`}YcU}y7ud%U?l9vm1^L3*d;3@nGv%%TT;PAt9c;g&jO$66B?=U*EIUU%idocu3C7ebPP%`S{wWmLF--ewAs+s zw?#I+UrqH1v9IcXT6g!=lRs2Wf7>x&tY}Y!b<}qWEYL&3>aQ3eg!FUnsWoY)T&^`^ zG)msjnRd(Tsk!w>RV!4S&7r{>enpAz-lDfZrsx<>kI z){Z?!Gc14evWd|v;6p|Hx7pcJer{s{iwjj#-uswzr>ZJ-=+9v@`gC0qb2XwN&M+G4 z>J?b8ZlP-E0J?ae;_%#J_svk#y$9Aq!<@Zx4!kH0bTdRJ=tY2Qw} zM;1Grp*#A>v;>-ZLg^8A>b*G*MoSWWc2_mxImF`ILw~oez@O%=>he5LpCKAFY`a1QTi!uCi-~ zTjwo%jadXjmI_@Xj>9wPBn-+&?wxzso?ru|kgv)N{I#ctkzVZ+$plWysQjfkP9|)j-A_+Pg@oUFGH4JdNvz!U1O0Swb&T2k&&2& z#zxl1kKqJc<3-FE;(?)f$ZyM|N$tmpgRgzRdf{Jq-_9kP5*s|FnDt>tc^hy|!_pJ9_><;ZHV z%au+LsZr(<@v(t>YejwQ<#&d6@srs^nh!ivcZ)_Ee2#brzYvgf{0$Fg?`RMq6$u2? zKWZ2F=r-AhnsT^|JLqeZ^DLB`HRd`*)D+N*-aZ`7QqARp(Xo>NtfeP~S?(QXwzu{Knfaerh*a3hx+&TKuxsFzQ6ZZ(vZeK%izu}4il(N16A>Y-BH!kFM^og&@4ckX2Jh?4@f-zY%Ym3QWma9=LBaR_~Pd|(1wyK47T@S#8` z0YhRz=K;i_&-_G}^-jn&tzIFWIuVgTv@`537*%!)DOo}b(5N>rDZkm>_ldCS7eun( z8|=)aQzIpG-0rH|of#{V6K6p%@(oSc&Ykm7y9S_GF6aCbn)=)NewC_@eUrn^ZSoN8 zi4i0lFEufO(48C~XG72^z5gcEI2rGpGdnfC5+o)i&;JBFzYJ}U3o_%zeUb5g74C}yW(N`?If>iGhY`>A>_GP7XVrSpAfU@FdR$O`rlIq zKt5&I730HRS4wi*Id|mK-d8_SjEu!Cp$gna*kNT?65TP(d9MXs-7Y9F&$r-P;+1XDt_TR$AE`eJmNxo%tvx?JI~nY4!EKB_^?BiArM zn@&%y`&%)el+@R`;6E6X6@MJ{HpvI+rFZIKI~jY{-Y+^&R^5-XrW>wEYf{SKau%%$ zY$YcoLdJ1no(69HpD({DG-m&e*;<2fkr`zpke%OU019;m>zk={`aflW zpNQbI2)4vN`OT4R#!$P55m>_BKCVRLm25vJdmrMjn3MXsA+Xp=ktt=nCB4Il7IlEc zK8ixJpmi}o#?!nZkz6z_n56mWt7EAFOQ^v`zP(WaOXER`JkO=Ts{Q%%&5@zjI`GM^ znDA2TA!xUO*f^hCt#1K*J_8X8IveSk4KFqMo+}QOvpN;MCaAC1<1iy*ATd8}vy7nY z>hdxBr;8@;^S}UVa)4V%gg(5o#^J;do`)h^~8_i|9Xo$T@W z<#^NRWx%_K#Vzs%XOery9Teq}5&8=D{VgDVO9l`{1r0$<>9k)m#A=YXo`r*aIIY1P z^MVaAUx!EVY8$B<*L$hdr*;Iwd<7n?X*T@F(Ukwtq#KD1UKg-6$>cazE!Hw&CI?X$ z6&UgC?6S9aS_-2+({E4_?DQ|x09_XtRx5iuy(Asr(kfW=KFxj~UzfFv1~mn$2r9+m ztF2#2&{7-1pL=Hik}UNxmbO+%Nv3FNe_5`w%dS~k{6&ppeK6_6)g=xFdh^R>YNa?z ztsvivN4UP;l16k|JRTqv7`E|c&o3LKG2O^V^x_=qD&MKL69HAKSLdWm(+Md8POWl>oZnp>jevOuS(}AS-WslBs3= zXQ}5#gksXi@pDC@YT7?&kOI#?J3yi*G=C&tgNgL~T1vA>w3fG0KYPRv&Pp9LbU-8z`CbslB!P=DjRJTbTd(=xaQ3-FDj0T{j=|CLYadx0?jJ) zUr-6UX0Q1?WxSR$#(VCO{t;26#w7N9Ik;x*e?6dj+!4F#`b(&jOFVB;i`+FWdbDAq zty=tKhCZA)0}bjot%M4lfm8-KzpKac&lLcQOR8)8dWV^uL&0bN3r7gRW(66~oMqzl z3u{&qHQKiPN)kz#KRabF4ZZ3&tPX|Jk{YQRqn7To6`f(bqz&^VY$2B2P~234b75vj zHwP-!QfmW}Cv{7O-B!5*9HP!=)aF0aNi(~COm)QUbfHQbRcfaHJ`5mB#Av-V!z|7N z{>Vv-F026Vue4!Zd&B`#+$y?C*PnR_-raZ3U04xc46h1d9WHjRCiWxlSu&~hP| zcz!{2>ccUs7jmD!91673t883lY<9JqT`MGGrIYG*V-;lFdtsCadt$6@C?-()XZd4? zxl%j$5e+B)5rNRfqTV58WSL=?V{`y>OLeV4`0NTp-|7+P2?ix=WLWX#TVN7wZN8Kq zz2yI*rHp$}?5E&dEjBVnW467R=!=DhI(&KpJ%ya5D-wiOuT(4(;KHx$z+IQOV}%ZCbe5+_Ll{T9Z}22hK?kb4(K*??asDxZmdP#Lh`;fR68dY zX`$iM?~1S!dVY3A-!07>L3N zKgo8d&?HD6^t36KA5g$zaKJx<*(}t0v;sRfX*0kjWutP{jabom3m#we_le5=K=`WqjkjF!!QaF5a|gC56M$hAMLd&PWL@*#w%mwuZ+>O_5J@AeS>A5X9NOMoFef+I}mLSyUS+AA%KGa zBsPm$=>)NuB*$rg@iwKJtQHd$Un`jEm^_EQATBh1DvpAoQ6Rn&1I0?!=ia-*iETh%$elyLncg8e-u zE+H$xGF0foXf__6nCH~tyW;Aen!!?x{=9^T(ek((EqyWQI7yx;El zO1GZgX)yVK8K^F@hp(J4$(`p&azt!Soafi8VIo;m+kik5`dQYPyu$N=$<)&XfQbI7 zIrY^9dDQ_CtEFhLdX{Fu^ERC(RSv>#X_rRa8n$sUOgT2%o)CkCV~+E4_wT+8X?$VC zX5)rxQ$5z&x;vY=Wl1nR{0{TH`)y*6n3tDYW_M#Mt4Xpp#{q)3NHT-)@?8LWPc#-m z0~9WEzxGri>7P_ULFg1dw870X+_$N z*;TiLCL@{{Pe`V(V>)cz-e_*KgI|P_WSSY-Hi~<8rn+`Ux4V4OthH5$x~XyR927Ts z^!<#ZzQL9wP1kh2Q8czrEyQ8z{vg!%>3#QelTG#!Qk1WVubOQe5Oe-#6a6!)yM=er zFNK4T+tMR`^XU#-aaA6M0${|vOq-RN+XLtsIF4iC#5NjKALRF0@Mx}^J&|3W;=3I zJb9zN9t}i00;B!!a2b>+dSnYUAL*GwMI-h!p(EK!suTCZhK$e`$n4hPcc_9$AKL&| z43uQEE6c8j!|Q8Bf2cV(AJ6~&#f5aT7VD}jgMfT-@@rTRf}bFUxUU$9 zs=Eit;E||s>oCyLzgfod{cAVY?L}1PqXI< zy}4QSvqYe>O46E=SU7VpUwr!h_-2XS;kN&>K!$JK^x^g;s}BD3?o{l|)kPF;nBSN@ z5fY*rN<{OSmhi@B8lL^=>Ggxag5#a{xWtd?O-O1M6+bP%3=*!f`{fm^BkZj@~ zr@`0R`5J#+KNgEP=9g41@W~$n6mY(N!C{p!Jl#qZ&_KRkMs|MKR5(FU)AO*~K}50Wp{(-z7CC zYkG)V-fE+r&&o4Pw3_R%U5|})nut98U8)=+1VcPi_BA&EKSwA%{P?T+k}W}`bf}a= zF$E1b8&fl|APxzA-;>X8@`#A~HZ2~&U5eRp2o~v*C!yPtxn-2F=wA5zeSH6FwGa$g zvHMM5SM%g1TEe@po+pOXR(li<1kr8P;P&u)v|!(%vkhWoheuDEl}rM<=5E?t%4z?e zw4c?<(wO*G{f%E{_s-Az!gsfh$J>KcC}YXbtuxl$kEgteHWo6@RL#+0uxuFlP z$;OXBy*ZEb1Z>}l#S{pe{qj-6r0-Yfj^_#_V><7N=)Aa&xN;Lf1~5%Q-{~-%l$V(A zaU64VzohmFgx2un-cD28H!P|cUUg+4Out* z01AqGYu?aYoj`lJN0gT_QEJ{u{MY0taC`dJ?;2~>0|qmtI5iSJnY9rD}DRCL8HyU z!dinqSLBoIG^YI^z8e^NM0|x%W;{3@Lww)mhqQ1kvBBvxy^uU zUy7}V&rx(H?q=ASgH4%D)6nUbVZ!1hjX@wZk3c&R);k_Kij>%*emnW5x%Nv7EY~Pb z;LFPq40Kn2N>!f|RhrLT32P8Lh5uU;0-E}oAYH8DyMgF59{W|UWI_MCqT+j;c;y{W zSFON5X1T4Y@qwxSaW)X8c*JV4R$PTz;Y-*dTQA8<^*J1^Flo9J5)-(}EYv-HWm0r= z7vSNx8>H&m{?VDNAx$CPW#`p2{tuXR4a>=ouqobntyEFn{+lWTZ5 ztXUmc90g7Ge%FNZU`J>1MS=;=*ESdhQoU{x`L5mnCpqorNgh!{ZWhmhJH$b|;P=~H}(8y6y}7Jr^pz1wW*gv5mR(S8v-gK$fcoe*lnUW=(*qjfGXcB7k#TI6 zPn8llZgC6wLH6$^oH>@*X?|Sk_ReVkY2;!e9SG&+*qhrrdReSbqZ{AlQ(?U_b@u5% zthYa2^O2g8V(gYoUy+GK&KqeTcJ-_qoX-=Ot462Kn0vAkKRXeV!niB_{{A zW4@rMxKI%8vnWSg#7b98q$(F}+ckngA13|W$L)#A1RU!0&Kjc^S5+$*60mt=*KzjeeN(d+Q3OP*Kg7MqgRP zZ@w85WKa_up7p>jcx~yHZV7c4O+!F4b7s)JIgphl?v>dJg0nKfb(~sb{iDG{1Wt1L zNkbB=iG)mMA*=? zT<>brq$wjsm|I#UT zl`mF_Vm89LqF%lgL|$FAWsL{}b}K-vJ*Ol+|A0w)E@ceN9e_F&USrKe)CNlG)j!4+ zc*_aPG%1BVPhthU&Z#MM9-@icSXUoS%&IW;7xXF_{PJ>B_f3n4G-00|0EeATYX_4Y z$Eb4;hR@2F(mozpzY<#l);y3fEZ$|pjo zYQIk!OsygNpP5p~2Shl1Ige8L-7UR!*;mzD=bRuZlhhLZaBjdvGLIdymIDEbc+bI| z_8B{E)`5%7@6U`XhIF(_Zv3<;cHM6&u=3@tUcA(Yd(H(%nsKlo@&;c|Kda-Zb}Lk^ zQ4&QIwinbE(e7r9hR##2wBvets${2g)ff}=bR~w{SyY)2^nHej+Jc+8kxfwS8e8a{d3@%|xD${32} za)x;v1MU|^s$ccwfDX@l=gJ!cqf^#Mp5k;pFeEW=ZD@n*3xuqUw8UpYvIO#C*(M;( zgF`7cV#JXrw5LI0zpN9jY#l6uoJ;wozAl&019Qu65@7&HTm|>{EowBtq%UFouIQv* zVunph&3bJKd>mbuXego)L-QofOymOA1NW^7cGaL*Q9V;CA)i2vLaLRT&ZU~JXtOLw z3)Rjb%EK+s?2V*GE6`x%nSPD5ps6R|6Ald!mcXZ3sn>%L`@_?%mzH5&vHNZ)HM?J# zWcS#0(jSV;2)n{8gtuOl&(+xztJkE~*|za=gN6U^%s-{DwWoJJ(E1)p;WSy8H6YYU z==cVb74S=F>&e(%kx#Udmn8i!wu|yRb!I}^bdSbE+rNsQ+&9DA%~I)Gg6=f^iuAPu zm!u-{$u3PP&nDsEwl{AU#kRJ2Uy~uSM0U*IGRW;mSCmb_)KSz2F1Ig>&?z=M7RN&6 zW}mK>yuc|hY98_eVeC=w6t1=H*4qMJ^H*q_MgHlCw|iLN;Zi(gTOjc4-=Cjf;d6bU zvNhGD%m71eL)lfUYg4iZ zr)e8M{7P80EJ$1UB)R4x%&5#}Bm3gIOi8YJ#ZHVNfh10=dgHpvsZex=JG^*=&H_T= zQTWBr9?^%{jj%LL;Q zyn0b7=EiwE>{+PT;jzUV2DK}xhA78hlXnbc7MO_wP$zoHyta4hzJHew14OeSp!cWQ zMh~kA4|yI5Fu>RhiNQsV zjvO=5)Z(Fsesyf*W1oHG*^KIh?r|8#Bu8$<-K!Em-0)tMmYX@k>YL^OF zUUfO?j3;4#MdZ?IqPnZvM9prto_%nj%+7YOz^lqs`4vfE#ijUCB=WG$@Hwm^wDny?6!d5-LsF*X?ubtMeVckB#Vw`F?zu2 zx?RTx`Py#A;xV^S80A5J-d>Qq09|iQW!3&HgjX5TSD{ynD|#tm1TF>C?_7RS9F4Qq znIE`RLg3sAr+MX6U(9uN!tSzzm3^5fa6e{V6nm@{++U|I%od9*gRPog8FJ)$t z0RxR#9TZ1r!yxFi)|1aUIS-Z3^G%gMwoJ}-~En&Vx$ua^3V&vZnSXtyUi~61D=2D zt2Zr9;|2Es=gs~;8k=3O^ntLj@Fnu1axa$rx;YKFYcA7^%b3{sdqAU`(h)My_`JlZ zb|Q`8y6fh*b`%Wwt@bH!adA!k`5WxJRnvrqLy1A||9Uoc>?@#|&m-f(@-weJnrpia zkR@5KPofXu4RTlXJBS#7K+#wk7%jR#zTJkABF2t z5F6ZjFuk8b_(iL%R(~=d(5MqFg%z+Qb?@BoY;RlyV$QFV!tda2{r>l`Uf18h=L*}_ zt;PvPxA!k^3D^bK=hF(FPd$BQ=^#t4ORoLpC3Zzc1*4IX(Ni8CCTePG0BB?bTkD(m z?z%iD4Q+R^t7S!X)dO}nw?h4L#ta_ktCnVA_l?iO($~#2C zZK5otppuf3lgSvslzJ}^g!w;{ll={TF7j?x_@_jZ9)HpE$x@T7$ucvZZyO(;|1~vY z> z$Y)OGQkJveLEc&jJJ4&RNFABV+&ojpS1XTueStvDAPkd#3pm~@f}6pJnk&OY6ymJD zsQr5Q`2SldG_N=}Im#+r)7fkd!mU@+UHNO-x`Ai-3tu>@qLD|?y<(D!Kc2V;SVZh+ zM$*jvc>!6X$AtHJg5*@qq}b1JM!HkD`Od=FgjMH0zszAD0{ol2we~Jc(;)5KmwZ$r zFX+;I?m#AIm1{GyXD-qu)tj)anv}b4F*j$x-m)H*N@2U=V zBiXm=>gzRkr>naM22=r+?)MJB5QL`)3u&eq0*S%J!fqs=bX;SAl8cMW|Ei@f3rGV0 zStkm35)0M?2|@L@UDql1*+K`=&=6JA>n6gS^q-HkhO&s|5ZGegYI%-L*`vhhCu{;h zBc%1=_oGKYgl;^gwzZ40>ijBF+(O)dj)YPo^%0lCGPa$79YgF}KRBfsNpKH>poXPw)+{!&;A1>^P7XlFMw zbFHYz1Q5XX07gf-^&p+yWNF%7?O#D4ibNed0BDqG{A7&+e-KzUIZdjg1& zO4#k;xTm9{XLVYE>1fS$pXmh*{Bs6#uQBT?%X$c25N6Ypsq)I`JLz>>7Gh8&GlWxU zxUezLAc}k1Kb5L>Q_iTNOdVM2-%M4QDJ+}YeHlvek)@cO!^b%@=e9St4Ntmrz})j{ zyVd}_N;PZts14KxFlj~EWSr13rK&K>Y1F>6 znnJFF^?yR?t31^-nT1ZE?#(3?6BDa?0qg+(^RM)Hx3EO8YuqLsfe>taT?ngO2kF1E ze8hXK0KoQA;IG5}w6ai^xfI>bvykGoqwGUK{-xB>!WNl2K33Cd-jmMGeeI91tb@%7 zyxLXIP>L&&8F!#9(C8iDh5URm?Y_g9^E^H|mt(r`L~c-Dt~(}=o;nm~tYZ5H)f0~= z<8HRfluxa5ZdzC$hI{KQFy%m{gRFSFz(j)`gK1^-i3ORUx=R9b&hAcHQ47}F0KR0? zsm-Z~FB}Ehe~qmVbe%2_Iv-raD1&i#&FQ3;-9clZKjkJRwBg#UeodTp_0>P3o#0Hj z2byF2ni2F~JxR4UJY1-y0rT=ojWZJP79IZhzJ;Iw+#}6qz)*2suf<4^xGKW)b*>(9 zoF5Ai6tK$fA&DIUN5v+qOS@f z4K@`Td7S1X$;b04bQhop#*&IL559OdhPVpRjU6u`M5DS9pdbpw<_XPoUNEIIV?zi5Tnd z^jNF1`8$zW8yjnjqKe;j@Sj1j|QVC3G?v3dglzTeg@s-Ah_O4zaU>s;A2f^6^Y4V#^t zqnr&QXHkC>a+^B0IbpULA`ZShR`hDW58$%@gC@zF?E|#O8`wm>;Sy)vAN~KJ1IJRQ z89Bbb{>==?)o|K9M$n&HF8Brkvd@53E%1l-cu#sO;SrTbnvd?)UW=c*E_2=tP;1<2 z(tcN{-94*IY}Lo4ceTUkcLMnAo4C>%4ic}P8Dfa5OuJXDw&{Rr9}j`a2M^64=c%R( zMSyGE;}Pet77Pf`KU*cdz-8GJljgcIU_Hj1J;Z8I`ZTYj^<`yYOGfj-*Ctwp<98{M znn_CI_lpcq1c?Lcde%g~Efg5zW}5z@ImaCo`=Ve}8+`?i^FCa;Wnf_R;h)-NMyE`*%(QVtL|&$? zJ&d9tBq!%LfNstHz=9i~5BLrHrD%C(pB#yD03V64f!(CT$t>i<LzUgpT5waA^^QJFfb6uBoCnQ5BGs5H69ZGp;A;)QPG+pBO}lWA^#Ac zg8a8p?h~&D>A4oU)5}dUueqC9uJ2Dxu4-A&heKIzApslg;l3ShcDLTkOfd*O&# z9Wi+fDq?Ct!C!AUM$TT??zZw=9=^Y>JKua8jAy3+diK?ie4j7^Eu%74R#uGgpY;EO zXnNb3DQpqt4pnxYJvQaO>uf^kjaiD_kH0A%wOQouzM5o_-smmvG8@vbt`EWZw=S-W z^y~7VfaG2vM88ge-LQg2r`998L~L^7*XnxekB&MIib9RDTZ3ZIk1c4xOHz;<8#Xeb zLw*pogZ(k?b4b5%ML0CPrStjuO$!l0X4HFI(}r_St2w{YS(Tg~JqD=d%+Ity$j0oT zwv3M`zY?UJo+}`u%3PEfM`D3E`EjD^y!VR-aH!cu{1L(;?MB~ur{9|lhkD}N>rYWg zSI8YE1qR@JyR3PmE1JoDW9W;`VwrJRX2e(E#wY?ouxosNZ76&v1JqCe3**ng^#><^ z!Y4U5a9zm+P%>{V^_{~NGESh&>Rw+lt9+@yc1?xg>VVlNx1~W7uc&Q_g_&_jnF*qk zW|H%QQKXC(h0`#Bzrx`)Q!>T2rVVHkK)n8c_^&8jQ|J`6b(iap$RzBxElw!*JN zZn+%KJb959un8#Lv@w1XS$b2ib#w4(!w2pzRk`V1B=_vx9n>Sc!dQcOjhUJzsAf{V zMpdp;C+Pd92=@H~>UPMIGsI&hdJkkuJOHZ)nA3lPD)&V|7C-@hVBcDE?KlFW{uzbo zpJiveC(8T=%aHh;g1LGL@|L?(Ek6I3k9SeVKd2I&qd;wlT%aL+B4wb2XX5-|=@)+9 zvano?<*Y{mPm0$}`nBUJ*vk1k*F7|-h5t{N(nU!ql@ejp{^#B1fG@T9`fq{Q>ZIB> zVfm`Hu3K0L{hAssBzzyG(U7{aCKTn^!^sE#A)pETX*Nao1|Em{{r&$13l8xWgMYOP z8HbG?ZqtL$$%7S)3v0%ffq&VjAH!;I99tBlRL@=yA1VvFb=JLY`Yw;SaCJIv<4vr& zWaM8T5B?O(iV6wp==kjQ_nWCfTHz4UQlsRomDps`LgWb$j@CtxZo`f+`IE&?N#zwDEDb0PK#&>KkREHPROdpNUk)X0$+3g z>oqiwuCjc#4ICpFk0w;w%NTwZ%|;~M6^d%w-3A@Sz5BF9@MeNbJ)1Gd#|c`R%F@dZ z)A=mqo!3UPWJ2#ME_8;{0GPt!S7Tjv>Ful1|1^xSM+=rJ+~(SsK1`VBR5#>hu=)G< z4Nd?MWdnV%xi6J-9fT5+bch-GeTHgO7zmN1o7v~N?9 zrwFA2ld0c1y6rYcO&5uiPL3IGi?oJUhjUhc7O3rCUU=4fUx<)Hphyy zDKXbjO_^*BQKS=b`T%^U_yda=?|`0x!W?we`=0sn5T1-|Gh9(s!MetS25)gTL28-+;Zff21 zAEv7nc86bEGR2RILlY&sQHw17dLIv+9A09v7Z70>OL=)Ce{Y~Elh4B%x_Rsh`o-}hLc@fI*ueyu>0^*VDD zQggw*4&FFcju9ww3VqNJo;12Vtl`h!mbbWIX{q6b-^ak41j@(^|POEk^X zC@L%ckB}Md<7>xqdhd@!8xf{y2JJy0bjjiQ&8EGkpLrxF%H0k!D-WI<$6@4J18t$Q z{55~c^Vdjf!3w4(9Z#Vr)5jqj7J`|;IAZAal0e(jnBup?4#r%HZo6l)dDFUx5$4GPRV*=?Mtf29owC!8(+1fTA z$YkR@*{9N{t=>a58x0k%9MFm<6MWvu?Caukq_KGl#LunHvMBXVLGj03!|?eAGirhL7BPKC+GY?31nK?7PQErsjB9&nGBe z&Sw&7_#BHZx52!Z1p7Aiu(wM6RAUZy(OZGjB5~563`|E}&v-qTUvbe-pEM9+oo0+B!!MT{?;vI5wR)GYMjKgE zX0A$|BvqY(Y>#m3=4h$}P4(t}L!Yw(>^K-j{Ma?MA`$Dfv(!!d`AMl$*YjVHRZ>tC zbr}l@(uti#ub<9%zY2KNyR@4ZQnP|0ck>w$VAOjP1Xa+jjO>w--y1rj*;a(+nZ{9W?p8gIqud=j}qP#Z&x_Dw)R#B)^Q3=0~{%kk65kq*8MinO*9^2ficJ`BIJN6>UKk|)dvT1KNKUfY%X`I zb^wY}Z;pc58k{wDOr@cavp1KHw+i4gccCNF!o>!5MR-&;B1q$SzI5I8G*o*I=WmDe zz7eSHQPXt~G5mvi(q+g#v2pEIt1JCdt&0P#U{udeq8(?OJINUHbkOeQJY9JG3h(Ht zm$7oW-vko-G5I;lHH9cR7{UcZ>ogQnU>qvq3}lt8@)_;fOxp5$3; zRIyH=qMX6>>k$mC*47JTbXwQ1hC^shKgYi?j#+oZ9=;%<|DT61@Fejh|Jo}UqS#ue zN}c$`_*3zNP4vM*7Auv@NUpId7HwJr;w5d-{m~w}>A9!((M)WW_?K4trrJ6 zqNVD&tBX|CQ*$Pn3@dD1zvEKhOW8iWTef!owyjs ztGGVAaWqIfX+N0jCQdQ}^Nta1iq^+nyNg8c0MhNio4Hg&ciiiOvX9XAHbS{k^VbaY zh`h4AYjJ%HR?^zL?eH&K2cT@rMN9dJV6w4m#|z7My6u?#whOi$-Ej40O_LF_aArTB zMHtOxDnjpuAA)kTf)&lw-hTTyU;S-$1{wS8YR)$Jr{KqMF)Kzi;W`1m3JpUwiZ&cv z!y7-?r!%?~1O|bD-T477vt%P=mpBM6@MRup8h>^!x$2mUFfH@ajhVmW#7%X)QlUG? zb_a>>2GlVacIA{z6(Q|1pwe^e?`kDeF;Vl7w%f<**KRJcw>!f}NxcHWZ^BcZaUt-_ zM1(0#@j9=APX^hYBVm;w%H;RZU|q_j`jg)+>wd=R;CFOAfC}Rlb0Wa)w~M-l5kghCzVX_*6~_eK+fwq$5cviFC|3hdkWI)tnW$A z2cTTj;9kj33t8GT9-||1uP@0w(H=8x^r?L)H8TLEMcU!{l|wG#;UM zQp`xt$&nb->)@TC0E}?l0@UnkFH)Iq-UfzOA_uh3e)e*>$HLwGa*TDfwe!py7)}>t z3H}d>NZZm{1sk@~%f_A*v-f4#x`Wv7yOk@0i_EJYJdvW&5{q*GpiZ5Y^YZ}}VOe{|C$Ny*9VT<^*$!6AR7|s=6W%aOVygI27 z1u@Mls@gu18`vCHsa0nJPgLA_Yvv=T7_>wK6%8JYYid)XDc>`EuYSvsVg*_Ot2q}k zyeB7Zfu!%$h9mJ)PU|{1n5Mld*VbfIIX2y0*i9;Fy$^5Fx+S(2hgDo&-^{(C#^Q8| zK76>{5n{gD9m!Xx#s%CaQ%4n&`jLXg=ttsNRzj@AU99~YZ*^5QDL`PP3<)bR_M28F zs!<&mei2>gwu% zT_cVvNB$57=-J?sU+%+{>d97folb`MoLi%>vXr-Uwhj|^_Ya22yrOwFmJ%3?KTG`W z$!#PcPuJxxBN&`^p0|Asgp3KJBRTa4scg%uTr+{_Z)iA2VHMkpUq+=4gXUyjtdaF= z@^tjidTFSRD1PQEX78`A21C5L zg&_CS&xIY8woUq0e1a)0w;)scGUr2s8F?R@#C67N6@mP2^;acJOY=}5$)NR8r&Ixj zP=j~VWz(IhDmGY5n(DUJK<{8AhN>?n6;y#kg*R_D#~}1-Pwq^J@-N+D*8I2H3D{SY z;|X-uV*J@|(}hU~KvL%0qN&H2z|^c+@3T;BZ#TsqX82vsp>S5EMMg#iw9`RlwF+>| z`EvM~i-W!W;H_$Z{SQQ-jNYLKa4%NwI(tQRF6V@WTw^?5Idqa=-2$M9A3?XWZ;El3 zx>zT-&PU4R`1?H8;?rWHEK7GTpa-V+tw(`tFb1O|ke~YIgQH)GuXa+rK{(%?KX0oS z=jP4YhdD9JgQ27j_VbOmHBq1L~_w7NSIlNla;Zcc{0vNhO*d$c9IoR*lASR zl!GP#ZdtT8lCFeLIs_^hx#zbMMTG`Z-L$nblE)WaZEYFk<>DTaQ?i@={K!JAIA@f$ zByGoy8JT2I1`kV?!I^f+Yrf8*=8wzYP1)?-S6EDGXrmmpVKE*B@6%M7L558p-YL|x z63@@YZSgwURcUb9w9C`3d!k2aM*RQ70&IO*(WKN|@}3Ht^E4|6Od{k}f?&c>_N$($ zb-uz3g{*+oM_eZZlQWiPr){fzo+s>+-d42BVQN!>S7+B7f(16T6bNw-mC>7wn$^ZM zeOml+oZ{qg>uZa$D7y3|t+>I;z+tn?MEA<&5u1ASO3%dQ3gu+tJb!=*Cnzd{1r^aV z`WG&h&fMrLV-u@Q0aJ*b<-+*BgBr+eHp)DlPk8;XFl%k}=Sh{YkTBZ&5vQADOAW(B zTMIRI+xXLH!F0C&Xs9Fn`2@)pm^x-v!mJIE~SKnSmJ&G#Xwe1}d>}A7juMV>Zix5T|PTe6%xj-F0mdBwMvC1 z_ZRBC^kLn09Eg)-tu7%FeY5LL&(5}%sLMdB z``)n|Vf4{{Z24?(8Y4Wp8<4t+VsEpp!K4wLLtoh0V^E1(jwYtt63;%xEI!Mrf_{yZ z)QKpmFJfLs$?AIjYZ?5Mj7q1|e+;Dig8(xVI-sDE8O^8FD7_~Sh zS?BIORIAIIZm{@|_3gzE^*)z_Va^@jN0BdJVaUI_ah!YvmuC56dYEUg+0>3>S1tg5 z8k?Rb++eS0UDGMZbErZ_-!mow9B>+xAu3*&*?Dc|;}ZX2U~P52LC2Zql$LV1pLnfz zc5lK;Zxe4)qRFIxo=Tw#&o2mzh{R#iMBZ3hN+WEtb%$F>UwJr4DeLt!AgNnAH6PA; z5LeA97UAo$3`xlV3vPF3ml}yOx8MDPYOe@VjD4U*m1T7w;yMwV6%94=;3SNQ6*@!= z+BluQWdyi&OplhcMVZb^o;LaBx2;VY<5cT+; z*_xl0Z(=C*sLmByQs zi3h0+VsgqJM<&9B$X&o4sWcsB&)2PH-$u=nFM0a;XvK0V5dP`^xg65vD=|5echbPq zqzAh@RLx;59~Tz>@ghH#wWICs6HkePxBD5AB#?7a%g)bE&g*YA`MiW`!o|>RoncvR z?z`wqwyw~H1qt+#i*wdS!jm0WK9=SJtO6f5#H}Ra~?t{D=~hQnaD>O#;We1%3a$=4`ctaj|L6 z`T0x1JHCFQbpeFRgN^PdO^6-z&Fwz1EU^v5v!`>mKIX#@Gf=2#9GelN(uP4(^5fYH zAPJ$-0ID!UcRkQa1SQO$?W+vHnP`EF#N$@eh|*v3)^}*U?-S$tM}U%~pgce#1;T&0 z`do_-CIv9Xo`EBJ=p9fg?5_+m>uin_i*?Yuh&Pn_8Ce_%@CA~15-aLAzV z4T3qZ-dE)-=)OT(x0=J1By-bLA@kdVPo>?qQ$-v)9uARN&cmbWPe6+^`rJe0U`tMX zx?Z{2|D=}ghR?8Hs1rAuv1)rT1xPc#FJ&QPzHQ;v4<_mq@Z&>IdA!=}UPL`4KcY4d z3JQZr(R;eg)vtU_$f7yX7HchmpNuYP2aPFyb0YRm)dp5?JXs16Za<9&DP1{Q7Veibgst{n)ohGl~0X_&!XI7RZ`M?@2vbO2YXV z{)luSr}oiL%%hjQmwlxPS%*qzus|HByb__o}v< z$kncMP)V1%jb+89;0WzM4nM3B&$Q=TLYk&H_%9`5Q9>)9!5KjQ|6#Yp5N_z}JinGtg2G69I z*-d^Ya|yr=ONT_A%UuK=8Tr9R;6$Vkdi7;V=qvs9`E4=?>~uajW=0ExI?8c1!@4&K z!d(tK(G~9Sr^_?55X=RM-53zZZ0e6TIqu0sGpkXQm+~)1i>16YDdm$5yPW7TT~Ec0 z=QF)mL+Td>Wfl*6NlR_R>;7qx&*apMYCAV1;qq~Nb+hytx{QJl^3Cu;h<$}x}g0K zY70XJwmgI)2`=xPq!lUM{%3Kh_)+NBibRNI7#k0bjvuAL=hg?kA7GiSQiP4;5?1^k2MNXO@sPaV>P_-t&{ z!3xnK&np8eg~nl46z4HUUFC=_fy|3mE0@eG{>QMocf`Qu_lq8BSV6y7@VIN9MpU>W zqv`AVQUkoWu0VwBmUnNXtPb0f|5=$s*@s=9m?O*Bue7LASv-Pz4thc%!re=4t5E-}pM63fXcjR>S*BF6-fEdD`<~(TC<=YEw z5-;fp8Nw$%s8!EJU_jLO?=S_=fBJmh-*GV~d&??Cn*6$2zd?nUl*r1?rPn+H{Kk4k zFrYml{NR^P67=m(>%@6>|?xmNs8wb#6_QudNp_z$GmmSKAc_4HZREb za*+L$^omgMF7dgxyW^_zjPFhA*DFhPSw;9R#ZzSr#w8_$~v#tI1W3YubaswIYc+%Hff>3+$ z454~lpUl^D%p865Cwo|fosJ(-rxQm9MTP3$3Z_cCIZV2YzPeA8vnK-GAuYR`NyKQD zQ2>E<|2_B^C+ArrqHAM6uswLar}aC7xOxPzG>dga(Au>3UO=La^hI|EGuSz=UJ`S0 zr5uDEIX>+Qli{6>jM9CjI@0ot)MI^HA=FAbRfYA7AeZ=fgPPt^kOR}FXMsBm0OjNH zjZ`=hovU)T8R=ee!w}%_%n=XW$TJ?C*CPIh&@B&Ib$<^dVZZI)zuUIep5n~IHS4NV z1+4D^6Vq^+&vzt6T{hBcY-iUj-jD78P!X`lX@0t2obrdDK>@6^I+T^Cl=Xs7ukI)y zdW?j~>zxK-r_!+2fh&mrrtNfXIvdj|@FO;Fa@gjx8s~O!bj-jfr5XVIZYM3w&10eB zni|1SI^iz_6m;Dc7nsv^E}fzQ#EHq^w`bG+1L@M{fN70w4enF}dik*WQZu)75SiFD zzp;H#cB2J~j(=Uf{KnF5HeFlBXT7E(dCVI1@O4_kR=`RXMyd}L1ypv};*`1Q<*##h z4ekJ`XQYaOthaN==5!a~mqIVie4PYy!?pJ{DvYz}>dI*qYt;=j%iw{L2ri|@50U%7 zmTS~fM+u~6N?``(D|Zve7y?KVDoieaySeW!Glh3B$l$`X!mPZ!s>s=+LsSIDO$;or z8v~?rN!#0JfN*hCZ3^Fv@IngSn=cDf@uT!xUgek8qu!SM@g!ZTLdIHD#Hf_WRvW7Y zyr$y^)2m}_OQRneDs*riE5wU{03|z>JG#P{jNs$I*?Z$9+?fhU-8k*8i}IMU#1YvVJJCYe-B=};y{ z$r3eKGl25`Na6Z1rsF6=%Cx=tz-ePck-*$AqOG%(^Lq{J(jHa!%RMzzMv-jwow9}F zLoTHi{d7%dDiPoPx2E5W>^0l1Siv8iyP!tU~{v}?-6itR*akN?K8 z`Wxzdy4HL8b2tnU2!X|t@O*?`wL43e1TqY;SR{=I?j9UT%z3|v5+EP59Uc8?MgV<3 z*_)MeTF;K|0Zg9XVJjqF-8Rl9ZovfPLL4v0MY>_(8VlX_J^++CJs9UfCOjbB9)4P9 z=CQe6P!ck6@@EOTBhdRDv+$jm*$?)nZs7ZdU6r@fRVdYW@~>O6@Gp!ngUFn`2JdB9 zuSb*0R}u~gAb(5EfigMnEa?1bA?65aM{6?9%t0}^nx~z{TooRrx?(un?Spw5XG1tW zSr$O@n7Ul==CSE$ah5i67Uy6fTa(f&g61DV#dloLxQz$u5(ivJ+XaA+#9l(#iFymW z3QvoX7av4!(odZpZ7ZC_coKKppNIKf0b&Q{bTDMdn`+JWSEE6?seyr{^}VpAKP{L~+VeXJ$B*)PxKRNv8Nlcpo~ zz!#267VSFFe0-F=)DtI|*yJNsm-GGeSsn6%3Kx&^j)dH27N=N`u=%4G>t_#%3|jq1 z?xD$lduo3dV81q|ev9gW_g$~V`ccuaZ9Dr#D51bWin6DAwk$YUx%ExVvuCpzj)10T z#OJ9Gt6Cmi2)uj0Y`6=Q0EpBYi{fVb#o;dhN>PQ4#X~ZDsL~|+MCDVTMq{nmwFjQd z&}5BKTA)Bb0@a1C7S#;9C*dPP<{hZ@JRg;*9E5Mwi2Xs?AB)ipB?eKLT?O zKE;MI^i^#B+?4wmpuH)l6%eRMO-7GYx7$NHu z#_`>UFWs5>#<8er?_8jTU$6sHi1zMd*-KYBJ340BSoT|)+MmCPabATw3@rD@hOQej z{ff(Zy;@V0%g{aO4G73??$b3^+EHY8F)uHW_x_q^VF2w1-2!^JwH7WvcC z2BR>lX>q5OYh%x*;#I?+*|cYuxAuC7;avHcO9G|@8B(5ugbU&Cw6Ts=6@ z<0&rWb22pO%L9eZke2GT=}%LwWM><~6&1%eBZb#ro&f0wPzhcx1D)~x$;@<4$Jmk^%gC_@^pX!? z7##B>G%4$mRC4qg7m=+r0VP8(X}6SHs+jwiHI^gZwGCHiSi6cqJpK0C8nR-yKqaq@ zcQ+Dt2~yeRO>mELA;ZdbIXFO4_RR??PH6=mQ0*QkUFM#7&&|qR4E479 zZEgK3nkAH?C+#vhUdTy%@P&kGjS~v?60j(KO z2EYFv`VT!bJPFa&>%z`QstBR_-X2Wp9@J1fDyt{pOQpuTeOXvtgt_AycSRtPoM zu3=gC?eL_dYddDJd=@9%=(F2Zka39nUdZDkzM#52o^=M{buhgE6Nu&!gi0k{kFBEjZ32S-^!a!Q95ux(%=&K)9MQr5su;|0nt$FKQ zqsQp7T=t<~@_Ky9iB*<>U0I!$@ItSxxp`qZ%pQ|iX@LcA()b%j2To*{&5qw2Xg9x$ zqNZfbJzzR&65#y9C+3EmrkeAX&%FOB!?ACY+B!YCaNF6!g(T#s1DWCHRN<7G`6fj| z!e)G6D?-R~{rC#$h}7X$GJlAS>y|t{t-w3?&l-!(J+b!r$)#udJCno6ju`;7m`U#tDuf^X&Z& ze3d9)ZI7YMxFzv#V9Ff)f|8EniDxD2K79XO?DooxcIsz6VKk|1<+`z*HV0$3;mAEZ`TsF-xNy7U%uXnou)PltaBWl5s{~i3Ltl|TQ z$?P%!P=Y+y+`e!Bk=O6rM@ppR2Y2>SUEh zH+$V$HKmmg2n<83sTW9ylc?D0^{=p70m*y&Qy?6jB{jhJ?!FjEIFx$)_wC$1ZmU^t zZHDu?qV*ZLTMgUpj3bmuBX;DB-#?<{E={l6uKCwu{J-*UU<&B8SPg-Bi{%vJbUTK_ znI;4L{nf7+Ql0Ow4hx%#eHSt5;?k=A?C_`e2k()+7#kZ~N@Tc*foX5S^%O*~o9qjQ z%#H+c&uZQB5}k%vz{PI6!O-=+tc=TK{b+M4u1CdB@7q&itYCSp)l$ZTp%BMcMbb^D z$@3`t+p`b{A4NiAp@)Yvwf4*qN?ckz>N^7x$sfRVMqI-Z)7==!*45cT{{NyEXbO}~ z<|`Pg0k7Twh-c65;ld36p)5ZViy(!BTwz{%1xgLK89&8jQRT=+clSg1iD8FZA5Iax z<@Wyy5Js|dM%AJYi_%GBg&I*C8yo6}n~GbHBDNV=thl4-pHTAt?Cb5V1vbqVWn{9P z@XU0-%3y9#9EeX$O$`I6%vqK@4ETZI<~ecSgt~4`pKgLloQ#5kf~+dJ*OpghUog^* zO-v*(z`T2%8CRI*c^Vilq%b=o17Tncs5dvxsy{cVME$%jt1QQ|0j4qx3f6;)OQr{4 zxhS~DoIPYe1kzv~&M^{j%t%SxJ_fbVFx-I|a)(j6p8fhUR(-rf3No)XZ1Z%9BO=am z+VbbiLaYD<{BhH-zKFyp?S5M~*Pq0MmxWn<^zf^L!BqEXtp8YX=pb%o8Q}9{Ta|Lt z*oL=1(fJ2phV(TxHPvAPE-*cTwvag79xn@UoC3*HviIeQX$lTyf+u=T63e=+37(Do zgje@Rtx&zyePgHQ4c-Cc3Xdnfk`5c=3>Zy{Qc`3qh0iv_#R_yo0k?A?PdUe}6Xvi7 z5q5a*eYPn$Gdi$&=N+Osj!Q2)hE2^uJo6At(`iRoc35hrO|x<6H75b9+|aeTCK6)e zd7O|}Uj=rC3FiZWCS0ZUh}693N;9?F6M_JTW3hre*G zD)e;r?*H2N*GauT)?x>?<&_)vP~~gYZ~{tfFtxc%KATwN!s6ohIhMO*UT}`T-|xlL zYQ%~Q14a|&MKd29{``>DneP0@wDJ84AYXkT1%13=F#8niDek^bp`^ByGzZKOgljgW zrW9sI3jdO;+iGM%y7sS)4gh20S;45)kvd0H5uib*o^uRoJe(KDHv;bI(tw*8F~@V; zujO6Wb7XQ0H;|X*+%RU_u>zgC-eDB`5n9=?0k_(bKGZt>y-j%T>y<-=$lRNQ_VRyi zXs{gm*}ND}ydRxqII8(3ShI$Vx^;?ywF}8b&$FsO(7!zruYZBS|KO_U;rhWG7UgCh z{S+#tdS6vl^*0t8w%xkwJr{7aIGIkZT4*C3Qcah$Ps2O>9iO&2H<g@a50 zm>|jq9EJZT0O3|;M1v8&ufe?DV_YzBGGDVQ|3B{;NYfgkYa|TT_^oc7%(zPfR$4q( zf1FE;wRl#yM-AjO z*~*9}SFr-u{>clKd@o>nH~4u?!2H!xfx3fd6qU^)ZA6+Zrkt-=t@Ms+S!u>(KS!Qb z)*7%ZO;pGh#8I-`9EmQ zf35=mXNf)0EYdD6F7GTYU*2X_VFcb4`HC3?8X6iq)nI3@L4N>Chw}ljhVQ${OU_Y# zE%zNV?FCC+$5aw(Gs=og$hlH9Nt;^|kZ=H4LO-U9Dd^ueD_rwzz}xz38)q{tzmMW-ghI|Ib6XfF zUFe}07{h%tu)SUazpA6U9cpJ_zEe*@CyP~fOB_u^v)STIt~tg4OONwlKoXTY(3u)G z+3t}k=~Drh{5=}TArvnrt5!kgKfj9w67Px9hU*TT)5!z{ehrTV7KKhqC;gVze@A(> zI$=KpGKGJML)l1RPp|@z#&=ktNVoEEt~EgBXf_h~ccp`)Ko0%A1`(WD0F1b@MDB|r zBT};EK9-Mwp{KD6kG1L^`GV6!fjNhZ2Pxb#aYlmr(A9i+kccikF^co~Y1?I`OLjG> z{@@E%@u5+^l(yqITAJG>amD+!R(T9)>%9g(Ev1WHh2EqMBJ2wazr51vwr|!@PK1Ar z2JI!q*bQOx-L_Xq*RzD7E+37>44a6LoXu?DgkrgNOujZUc!A2MukFqSkjdw(-eZ1S zivl)OK4X=C30403*hCx~GPafHu);N`CFJdT_q~VkW3;521sK7qCr8An`nm!TlE%x7 z>J@B&>w>o#_{svJP!E5m&^b<6?^ACM_-iot zcJt&Lx!uN)Bi3gUcu4|l&>AqS#1X2R$d~kl&{_3UT%H^(>!ku-XYZW$R0^AmQnOUY zW7A)_SjoFHL@Z?#BGU7PVG}UL-&=^*q&d+%Q4Y+H9jVlzOssd~1x|(QAx4QLSg2{Y z2)Mhx?bB^iaQsK&kPQM2cK?Tq`-LAlBBNQbt_(WQ7Z-pUU>}GrW^8##yU$!UClyck zSB3k!fV~6P=zDPD=;v!UxP-cFj7x%!M-Gtt?0u_>0&Eemgm^)-Bm3{*p63)`5;h1| zAY9x`#f6aSh}3NK?$X_8ath4%Afe)T&Z3<4@Tjh!uDGk5KKg+tXCh4)sC3+^jt_Kx zz;OM-6Atk@-G&;S2}9!n&zmbE#3SOEupgQZR5FTS6h*Gp(pof!ECcYRDAxULBm+w! zS%G#Z@9i)XHfOr~mD%EDl@i~~*e{OaA2XNiR!T1|Cct6@>6t>Q^sBMbAy3>%a@5%S(%`L>2i6rUp8E2=`Ee#p*<0qHF{DHkPJNd%f zzU3200kOV-dZ{)OSA?}@-IT&L!x&YhJHEm#3;3U_OwIq1gFixp=jY1$w(w3!eeTt( z`oJ9kjQD<4|0O=Kq=ah;858nsp`_*VMJg0NWX*#eavslGVT#HIEHvfy(V_(4TA>s| z#gPlLiIL3bH(3?GU2SsPkvjTcFC=8l1o%v7x~!sZ^hNNW1>^#u7dTBNyj^vNhc+Lv zXcdd;We!Y$C^gDJHowoGt0gQ?LQllkjmU^gb^Js}bY2>8CBmya4s~ODM;4w>XC*yx z86hjiR{J#J1^Xr=P9&+`3}n^$VZWY&hT~#34{zLh&ns{+NXY|cWlh2G2WsaqijEgC z%dI>`C?3R3?och~`FdcY=t#omrN`8!7<9lUKquVg%rpxIQg;J=& z{30-?VlID3;Hlzj8^6mtiyF$tyC&)7n6fEukr0Rb8RaM+>4uv9UVQ6+&63adXGE;k z%OwAo-0*(^{Am&|egy%OF<{0LYdj0e=mRBs7)Tsnfm$Z#SqPOqeS5<3ICaQ7|I(A{ zGOo1(m_5W-1ccOVtBLYK(Cn+#Chy(tDjOsmA?K><2S2!17_gAHd8avc1?-bnl^rxX z4NQApgXVSapy#DQ4KgC42aJ;bJxX&B+oBG4v7?knHz+R+X?Ob@Lcczra9lFR2~RLJ zW>sYd6G+88shr=u?HEegNKPCA5z!1Gq=1ZIAw`*V9L|Ah?cYZ_qFG)Fq}(Rmi36hU z{F&Sbq(0CvhhdzuS>TZMy1im}n`%NxAQPzS_ThdimO#yOn@cCMI=TL}c(8nCKb{P2 z)|!SVnrx|GEkfq?-cVe^4ear91Hh2aGMLgc0)U>e(r#F>55@DwSQN40Sw)8{$stI$ z*zWGz6O(F@U{8x#nw0fScW$pvFR&a5n%^OtFOSW3G#;xUEi<;OG)GG<1U z-ub;HNl0<1Xrq(^j6Qkn9YjHv`U7alumIS?+c{Jse~4)tMBF1fQPB1^2+wIi-8=xY zSoP@HdgqXm8L)F+0(3jaW~P3}Fd^a?2M0%tcec0pGeE6g=rp)wArKNeJx{5*bTcXF zMeOcU_ELaYpPj&K`lYT;_<=%7($V^02I0lwlx;5{(B^`MuNU2it}>&pAP~p_w#1z7cFZ6VD$5lciB18W8r1$tqg&Y6wRRG)pAF7Cz z4_u%JWduk9<6cA>%R&x=VVmmSO!)Yd zY;Q8J3fEOK2NU!?wr#yPlK++Vq9`sA%J8Vqrg%Mg#-bJeswJL@ak zu_5(mV1$D?Wm&7|CwtQZYwu7g$qziHs;%7#V3TxEz{!HW>%K-66yF4FJY?K=7t?{) z%+St4m-)``j%Y4D=-NsL`}w|s|)-zjzBN^_r%EuK+9IX1Uw#q_@9dojaFLx{FJYf zXLz3wBIbsu_;t3w+V0Faz_b<_HT5P10@Rxw(05F@d5&*cj;_-R+Kl8Zw_bv1Z<vGahl@FHuB1STzfQhj`>&LN#pxTV&8-N_yRfQi=@sTpa+6I+^!pdj@0@s;QRs1ie3SX zVoBpfA5{8SddTb60Ggd^$9L!uz25CaZ0PG|H+heafMFU4zDC61Ik;~q&7D%jJv;MU zxzB#R>6hMTMu`*PFtUME5&2tb^ClY1HUypzXj2xEzgeU{H@QLvov4fa(T`AI8$wAA zF3bNB6Nwko8g>C7A-{fAD%9!!5`fpI;A~DR?}fp!6R2eL=hZ-c_YR@_WWl5e_*e6r z|GZ2iBK+Mf+eRCI>jrSHxG4xcaujWX9u9pKy!ox8!8M9+>Ndz1p8VT-+yd^kxq+2x zc$m(66(H+do^2;N2gKDVeAt?Pr>#0bii9^+{V2<9?||7Xz>usb0ACJnWMI&G1{e=1 zrc)UV1k{Yzdt%tSgpaClm3(#=e?+ruJOMe!cWQXsFlcc~U-!enzma%(%|`rTWt|fZ zZ3PJHUst*R^7j>R@6RN5RI~K{V{VOtzZokn9@N1%pdssJ$?cB8WAm`;5f$)wNjP=R(D{+)HUkwF$h91;a3{i zxh)@XvTv^M;QoBgX>A_7P2P7pi&y@^8mvI?-+zvGI2TvU+8vnk8ToxH9G~^M0GEL5 z&)_>iPA*9A2k7$-m-PM&tB!!zwQ4!y>(&C)&*DCpNj~9)2oT-amU96@L4*nO{S4YM z561!;yVwn=sj0Wvl-6?n0<9yn_W*fQY)=TZf-Ai*JOCVZd@!cBy1UeqWb){rwKpf~ zzdZ|xjTz)hs)5#OSH0u0F$%1Yn}lGE)G~77H#6wy9ydu+ngJax7A|pV+P*?`j{H*% zeuo?T3a%YCBqjn%h5tU zfUR&!PsOL})!G>}t$;h~Vss87qp5}WR<{7-^MkFKuXJ>Dwdd&h_Qq?Ep2C!l$bh;W z3>rk;s0Rw?cP1t>lo058H%JsGXXTrK+u#GsF0e*+M;Ss(ci zUP%4h-xgf(bzrEH4RU-IpcL=h^k2nNOLn$fqGD)M=bg?D^-cN`O;mDTlP}HI9O$RF zbYtIo`o9^6k;0s`zNm-@7`|vUUTTnZc2{`)C!&R^5$Ib`EejZy#jLKjsw#`0hAd&v zOv~si&;aQ~Nn}c|6jbb@SdVbk8OOT1f_>E5$HwBQGdn)(T^*WAg8+-vOpvpD0V%|* zWRaK-XjpLlwcUtg$3MOE3uz1p7qVNq=FXft_1{Bg?`?~pzE6Gq`t{=WHfkyZOl1%J z{uy-Lz)`|&4Cq(lU>3#w?Sd8nveYC_wScBZU@cgejCcOt=l&{@#bhP>#CY^W(S|1~ zSuc11@g!o`R+QjITTjo+yt4!F{_m^&8^Je-y%v32JdZeYG8OT7e}UkjAFWG(X?9+Z zjU17^o9OF%rQU8H7ln|ONQ8Nx$188>(>5>2Wn>Vn%{00XKklQz&4Ug=z4LK|!}$aw zcE)9`2^H|tIH9COjRd{bT|0oI(9Vl#Cz$MD_pZcOq@PJR!Unw?ya4|P&%HJJqk>;J z-599z2f9~v3E0!^E8YUtrRXl(4mX~394t) zq)$PmT>G|z)rdc8*nO8e`*T8t(zb!}?|13**n}Tg?N%=D!@;fMY}YMzjfVdg^)7m%xGZ@152PfJpX~`ahwl|Jv>G{)pgnVzwF{&!*?=HrOd1 zlPJJ(UcmL-(I-i|*6(pXHV8 z4V+-?UnB#pvpYZgW?l96-;sm}!t@HY9nI6w#McZxE(1gKIqG~GqlL1Zn;t`0&E%dU zS2=jS*nF?7$6!e_9c1`O;dUTGIMc=`3&ZN)RMXX&0}VdaJSgicN@pEUQygrzq|Jv- z(|~?6w14$jPzeuYj{bz^oaQNsch zRH&5DZ@Nvrc^Vb@BaL-5Kl4?CK2dY!pEn3EY;4Gb+)(9z?xTNwXd>dVO=PgYvOnjM zc=bYUXRH}>hJcDDp++ITCd_n6&}#5wXTRoi@gVs$ufR`AQDE@-EAmViAQWYJSxxs& ztt;W#FffN=ckXoK1QVI}-Y^@_`fXK28`UfIH{y4LVf8k&xXoa!_WwuMTLx4aecirF zOCt)Bn@~EX8zd#Aq)VhrQo50n?(Qy8x*J5gyF+@@4R>wd|9j7S?mg$*<{Pk|XRSHM z9P>BmbXw>z(peHtkF_RCd+)UXv+=g-@B<1Au4mFWWjzu7O*U21ssSULVb=bq1E1|Z zR&wJZ8NfA_9{N#_bbv@x91$-&$R_u?-@kDu*fS#lFZwW&gC=W zzheqkPUCrhnDqr)cqt`3HFVBY6^J;%a*+iw-juhla(z9Ok zvjQMkjiGP4YuCQF0H*nZ)Dk}W?S)?pJq&rC;%pYuDNOLQ-0Um%?BSE;+t?3Y1~VIo z{eq5WlS|_ZTkZA=MbkfigE+CxL{s~@XsequLD;Lh2CG5Vl=QB@P5|+;19AJ;Q$u4Y z?t4IZohUsO_}4+$l0$6|yhZK+?I~;WR{r!gE&uNVRW89`Ks-V;&}()T2cs}*2n53G zwEqeQs%a>D{=c8$tg1e(%va=bC7W%35)Tv>7Jb>ryA=2nfjB)pfg08XSJH-Em8lr3d%f3hW0yuJ{k=|lq5 zs-+KrPR(;L*wATmZe|x5(eU}YU!}m7{($8R5j;5!-NSMmuIx&Kul=957~ zV;N+?C`~m{!b3tf@1i+S@tO`Vmh!7$`mxK!j!F7xFu|D={jb68u84kJ*B)|&MH^0$d-e!UZyCpBa#=9 z$L)xKAb2y;GW`Kh!JJRZHip3kHShl19e2FAgb3}<`}WA$4KP>Pxo5(YYRrlBSL!tG z2-Ws4wwK8(O3itW(N(L58alUW-jC%1hHPjH!`uHpHqn$!SDSFpMz}XaX|d0s5Z$Yn z3P>X97L(8Z1QmtS4l0;k6PHSRq{>(k6DlFH(et`Lcx~j|33*c&g~ZVfZ}*RQ2#tGJ zve6n9PgG4(vl|U%9{-{RT;iJ-yy`(UD%Zs-KcwDkx~-tsVgVYZjK;6+?0+Daalo)T z8BovtEb2-D{muDPA`5KR4&KPhD0kdG>tZ1UAm<2T1_m_|+oQg(VBUmU(Xo*-4aKY%uNUn*8s zKJom=A6phzQ&Te^%|;wr zI2Vy^c@fUHkanutD)Yr_d6-j%W0QOnixx=j7ccK!5#?#lk8=fvmkmea04*H3(A1`%PHP zpmH8gTpC)x^o1xrw&U9IAPc*>t(TWfeOs)obH_FIbhp3R=g!R;4&s-(>$^VFD!%P` z_t*~JFxy`U1QM8vBs`&dR61`$fnSIBrk1f}`Upo6bNMe`Ld9+=aZ z%^G+VlLo_CQf$Ty=nC48F+d8+c^g+uyWRAOKPZ?we8Pes&>$*i6#zd_l)5&SMg}A0 zYc@bAo>{FdOlDoOco5aeTTZ(bK0KmV`DpZjX7ZXip;jMR_QK8qG4|WQ{Vz094{!C>R*qpq%zg%|IGNcxCzY@l!mS=YzPT{bSh*#|&gxn0B1KX*frF zUuHOQ*}zd&2te5q%fEm?J_Z(bTCY4&!Eo-s+8!`=1^mUXUvJ6no)~uprYZWzK8u9r z2*jVrNvTH~uL}9-_0bHIi(wmoc4b&Ln8**gj9V`HS8ua>@|8ZD$@!Ld)1{- z-h}A4b4!nq0`V!Y}>h3o%8va!=Uju2W)yuA!-)x%*|J3z=Tyg(Ej z(vdRsv*%P=H=Sff;2N4NB~gD)?wGX7nM%+4s?jo`LU*P1NMOOVQX}=$R#&Hz+S?0D zVTH?dO1BluIBm*e?wj&nrcO06nGwNU=h`N?oM%AU+mnyb?0&6ueg6k&MzDml^-4=* zy;Fk|L@~}GdMToBNk`^s-i z$kg19$ZpQPG<#X1K6mPmH4t5KG?zZCBh_8kc}WG6BQri(!5Wi>`w-!4XT!D z#(^GM9Bdzqe?DBO{|tQUY#;Y0?!Jp7-7SYtl;~u$Pl3p+A9~SB1?4gEy!l@B=P|qmV?(A}7Jb84 zg46^ApyA5`o?|7Nu_-1%ox0l)pxG!twFr2vkQ9x-JvA483YpsH#y$xe&X~f)aK4~6 zb|;)7Vz*@ya;dgc(EpC;nG>IOcDq9RG>DClxlh zAEGD58{mBj0PwydoegqxKUglO1XSxk-@ccQ+oGn#c{ZEQYR{RTRH1wHiIIw5V9sX4 z!Mfmm$|2~12~L2TZ6hgwj;en^y&vHaRu@mq<(AiiaYxK)M2>|}D&!tM9O~TgEHrri zM!n3>$|BNSmPgW%Q*fwW-9p+5xv2X`A9Z=)u^Y?}FNT270_?3a3s5+_8o=QPYWJ(m zUcwhw)@D`_He^6WLfX}>bb=+Gl$MreGeVC^0ZA{7({d)0o;3`5db&=H!D+KJ5W4#< zOsm#9%FhoTsM6mv$UeYVm>exNe>O9F-_p|3FqVjjAcz!dz1&hpKN{ZR;o6(r_IQ3J zYp%8&A`wR1K87g|}2CJ?ZvY;LD zIfJX)IPHIlFwaB&;rH=fx;wt<&U>hvi;mQVrHH%45k)aBsR4A+)60jgD*i;BD)$7) z@aGN%2D`swE%-8!fiZ;?CIK|Ms?ZCy!)GhA3fPB#Gw7g|5K@kwL7Z?yy$V_w9{3`) zWtfY#FDgQX8~CYKQnG%)K@L9u{x{5pB)6)Vnfwlqxzp8mdU@mL2~64l9-%=Kk2w}) z1T>C!O=`9Fxt;hADLTbJkN=9N8-$3+r$+FdlZX(o85t<%PCfHHW44h@4%YFkH3XX_ z@&=4A(KE{hUS%^Qlf+)I?m_DF{@r^Bo^f>7;MJAjw_srab7@?kM-o5#PdyB?rXc6i zV;1PPibkP?49{&3LVog;Tq;Jte((ITNfT=&6&bogI|kK|ET z*2#C{rqF>1w*1`R(Wj2&R0$Ji3)1yH1HWV58J8`|G{PSdG8Xf>4GIe4&vCP7R~3nN#z@VtT=Jm``&M^8OOJ@pd;0$_GBhs8-Uk*4E+ zw5+?o_N${VC#{DH57T!PuUEba>3BGa|H2^uw5Gh0(QxgHUt%?pJ+6i*C`|fcgQF|w zw`!TWUHRWnd4I;eS<_!QACWAtpc4wI)juol2>nWM*m(RG(G$JiISExoaTbe>-HLeE zzMt6gvh_0l^esNE;S<1Dx7DI*+?)QBW5t8ZD13D#u+-*3E z*`G|wbqQaOd70rN8xRto9W|ctqfIj1c!B*Tec4%FGKT7}@@_{fVxlqmR;?Ss6cFc? zf8hEzKyb!&jjmvJwcEqdD2kjF^{(~)eurz*cgx~#b3LcN73v7YNY0F~^g~vTACZhx zH*Gv9+d`%EKV^6V*NAznr=$hB63Rcs4aXHmh7jWGE1-S$KIXPxw?aHu_UeoKIj9OPt$S%9thl6h z#E#TMTD@>y=MS08b5FUkDD*u1wn#WC0u`rBx>VBJe5yWAS`oJh>um3=%oa?1op7Mj zD&oz!{F3%v<1TADA>+C!wBZ#4O`#>TN>i2HpvCZ>xEW&*5v&l!fi38~P@Hu9bw-p`EoyEb{F7Ir>aefoiiQ*Yv`e|@F{DE zhhq306h+GDF5IqDh5w4ExcBXyTQ+7ti+859GqFrrs3BRTgbA3FGANO&9NVCCW)9EEO#$N5p%%Qff@}uB)q{P3^Sb z5J$c2KvSRd=49~!G-dQ?>A*bs-P(zT((}NF?M5;XqaB@k<5k*jb%0lKk*&(eko=?8 z1|T`gDbGpjeh_sDZ~25XpB1w;o@FmI&ainEd7fxyGlRT9Z17FU`WvuKwspYrdUHe& zCwfa&2K+lJe|*SUm38wLK@MVFcvWQNJV0nAX^it;^m$I39*;HgtV*$%lWMVlXqlbu zNWCKE4e|5r*>BjaAT|M?p9HwWjK7^iWyj-%Ep7d-?}2?@Z#2%(sDl4v%~zn*N8mXyrD z8U)YvH5z`-Q+TAm;HnmGOJLGT22lam0-(1T13i4?^~Lz)*N&Xi%wvU_6oo9{5gOlByPvq9%mlZAT1$ z{$&6>)xQ$u;^EbfJY(SIF$;BF#lPi z&CnA|r|WNj7l`ky7kS#M{;;2X8yE;eOjT&S4v*fgth4zDVnPJ96~M%or~3J4LBVPB zkT+#c9rVboFRyT_!>rU<2=6;%-e@|)?pByl|17D+l(*V^F@zbV6L8yNRH`*qdF{E> z|8u}ov!f%nOgSl2v7!QW#-bT$mXfzIUh+$*_4WWwg&n*!jfp1|HQ$7%$P`XLW|UMp zmvAx8@5s3M9iBchoN0JfDByfZTQ>JK8CjkcZQ=*%Tt^!{5;OXn7f9@*`N_U;&(X(7 zdpp7A8D^$VS-b2+fOcmaZFsQA$4(KP+!$`>i)X_@Yzxesu;GVK+gH2dqU*=OY4uub z5)LyZjbC8jARlo^Rb7hHB3%1U1>3lW$hw!O5M=J~H9737VV^2$}7g!1{Mf1r|E`Mmt%jp+88b*Zx$)@6Wfy=Wg98?aHs}`;_r+ zaiV4vzq97p)Jxe*?3-zW@Z?EctbjuZW~hy{f9_ zg%1RT21$~_&Ic5CertTim3Pxc5&i_bMdl#)9+MT;t?I|FLic~4bM65KKcvS2Rt*!V)dy`u?xz}%NdkealsykekEkLhkcC_`C&pZ%fPz%MyH9*bVRN-M!*CD<=apY!cIc=E5`yV3eE54a(LL98UJfh>c|A0>U;qxQ z#T0|?UxHS(BBg-KPT}XdEt(K3usV}S$ZiT1pTFAIZEy(QE7SP(?GJ|X!-{?Kh|K|34NF zPU?{owe_6tWiR?i1&b|4DZMN{@vWk^X<50EQs6Xra4ohp=#3^V>fPVtVAYHyQZOUW5I}H$=;(HN^0as6 z%Lf1OOt0pLS1g6bdwoSxC-`(jW}fKdDF#$ua`4j5tw68Iwx^lOx4_aZ4>OqmtH@*U zt=EPd3~rQ_*R%lC6=3uei>#$>Kh~QFW8Qk+-;9Fom=&y!M+_!4iUI3nGJyrjP} zd)em*Hk9VTveoh><>d1&cMxOd%!o3fiYWM*&-gR~P%txGyF6zg=fD^78(!=cOIyqn zfCYrGn_|}rm<$mY>ojsscYDJb&#s^D9v%)^i7tsAf;nrd^-`1B8R5SppMn$dL1~$` zzk8Av)%9-z4R{AEa}ins;t*V>U)F77{rd)Xd*1QNrDu!*UPXRKzI%#WaHryS{oLrMm{K$ z)kTY}n;+?`vfHO0uy$G_(=F$J?=?vTtvWs7spo@|Zr4gm|5P@Zl5MwqFjVv0yjMiF z5D$>E`9_UW2kCd>$ME(v-yDtjcXxZY1+Fx>U%w4yWF#vG3LPG$Pb=RFX72JTvA4U9|cs2_7?qixJ_=7j4( zev_RhG6%>$>(r=`$p{&FGbkwTeIIjmMsJ7;tE|R(rw|?ru$fP^1pRksRI=LrkbZvY zy@XRBspGWGPaoXhxgI4*zLfw9K&YXk=TVieA31nTc6p$z_N1Rkh5gqBNhwH|pP^fp z>9wZ6;Zs_wtE>AvzAG%8!?NX}ZC<$f}|2ovFHt*iNdPW=J zLsD&(>#DSuZFPob@Stx;#0}aQ={m^Q@W|Lq_GnQU0Tsom*peQptrRQ0y=M|PCNXEi1 znF$Uy*bKuHRhG!7StN^X=tcuhz3A(SRi|a}epoP*E09m4 zfBj+`Zh&xqA-lf0>Dk?DTag0(hwn@F4B=WVHuA-)Wx45dTX}!`d>{HD3R=Vxal_;? ze@7pR*vALsG`T;%p)UD3(Hx9nm9dnzbTv4>ux;Vazb@W6H_f@rMWb4Zjb_w&M6je# zN>X%A5~iR6*ix7*ojT%-%J{lHYyC6G8PA%iq`U^cb6H~fy;MhryESmS1MZzOILI1F zC=JmRu=BD*&|LPT2z%$}QWt6}{HFg0-pOggn7_201ySO!GXW zQe^d9lHOfv4m?boz|>~Y)YOQ%JlA8N$8M2_#{3m{OaGeKH#T%mxmK5oj`y4dht|hN zs{~W1qkQrk)G_w3>*_Ureaxx_qU zbX;=%azEPzeL))mbBVQJ<0RIj7JcVm*3|FW@2GBcVRc)mF!ku6K%2q_W6kJY4y#U! z1T)5Rh#pxSo^B2~i5upc#%N+zIo#^2@iugu0nHu{><#UiD)xM0bp-qjf+nm{kLRlv zJ~bH2r;J*)W0_2heLvQGKgSK#Ejh=*tLW~z*95Ge5d0i?BG)1}or}fdE_VeZ_piRM@4$CnKzR>9dEJIZ z!W)a<1rF1;PgUQ}3*=IIdWBuV{9*{I%)-rdp=JUt(f=Z>^Wp0iboGwi8zjGU=OTK3 z`aI@~5%uDVbAxCLM~U3PTYDHRC_M_fZ9m29K0jY&W({t>TykTkQ4({l^woLcb_9N; zzgTLd2tj=L0UO8dXz@%e?7BDc)i75p{I5f%oNVv?j-+iD$mUQQUxJab(^j*|kVl}M zy&r$3txKF5wlJ8i8@_=a=h@ zkQlnjTGoxb5;fdH>&3AK-Xdi$89t|~w}rS`EsvgcCnGA6(sBLrTsD{!ae8$lfm3A` z67w}K^jIT?=ruU#K)C$psjPdFRb#Anr?bqmELKY%Qy6V0w7EO$d-FY29v9Ct(<3T^ zeUF-I@g^)+G!T=1`ua+TZ2$PX-x+0)O3&-G#MtrWWuf-mIv(c88cNqI8m|{t?@g^4 zQg}jgx~qq{l-E6YpumHbnbL%3BddRi;7H=n|5_kdXro0FGm;Hbl=x#Yk<}2L0va{$ z3F2pv&LtyA2OV*IBDjR%;Nk0;`Xk>;wla;8*4NejfI_%1Px0O(czyx^s4mbIR6T1x zrFQvxsK9idB0ic);KFV#C%A|_z9F9C0{3GWr^GqHZu^+XVb{mNT9MoZW;f%C46Fkp zu*3fDQSzSLvsAYEaGh0)^A5Q{=O-UabnQA95Ik?rXm`MlGw_U*ax3YU*H={hXx#kGuK7hKE7&KYgUpatDpxWwKH%J21WrD^?oly3b=Yhw^L5jpG7TDK47sP0wp1`)MPAHwf0cFCSnc}ZB`gNhL9{**?v#l4z|s#aXAWo{ar z*0%L6ZIa=hu}MS}&@eols|+lJmTJ4PPapqY`tX~*k%dNc#_#bLftP-WJdvpac8kHysK;26(*2{58%n!3^nOh)KFkGqp% zn^`3!)s`CX&2pZo7DXp0AEOg|D&W66GmLuZg{&8Pd1=vUaZ(@A%O%^mcHlsq zmczAkU;q(FaXF1&k$2`iukHA)mJj80bvOGuC^Am4;}Z4{LPusQQX-uu)s4_+JF`KwgcZG?XEI~-yZ^72QwM9^XV z`$C7eDDgEqfDcboatBrQccnb#;xNf=ST?CB^?OodHnEpi@{UBOgF>(Af}GEo8RrQ) z;Dq$rv#Xr+5Yk3*OA}Xcc>dsM*zV6AA>j&sa+7*=*kK!a7{|isVt9bqokkQMlt18A zM9Z=WfIO|97>%N7RCH_+?V2Njj+Gl$hkgpbbusMd=P8(anft&6#bM!QK5fAbdCYXI z6;YWlBL_qVpM~ZoAs&VOT=5iI(R>DWx9SXSnR6B{AH7yjvtp$;5q8Axl9J&L8|Oi} z;6Fs+aXtwmTt1Y648x#r8C(^DMgxfeoCuvoKeo{L^#=-UaK@qF{roJ%=i(}iQ1bb}c$wL!-KCsYYseZj~8E6Yo< z6$S+HB^QJZkw~zYoLH{Y*s~cFAGi>B*UKyA`4Z*g#}Ah9K1m%8M$FGb6wt-R#rpJy zG{DRQ^1e*1!T^CcnZbR{F*Ee|*x-Fd&HZ|WkX=#(=`Cxm%74DlW0{;O9kc8si9ttS zmn>#z7(^O++Tbk(3(lRinF^N|_%0pzi*Fx~!*nTKIK!<>j^}0TAw!RnX&%**Xki{;-D?+kC1)1S1jcuL5=FP zhx@#qvljXZQmV&0t#IvZ9cf7C;e*i!ECd}liFv<@(J4bUZVtr_+)fdsf$E<}XOv6$ zH$KDfyzaL@S;Mu8BBKSEGyDm}D3P;SmNyd7ZF1%WabamE*kjS%jV*0~sgkZFmg7GR z2+AKju_$8$e_X^0c}c`y(e!rJNqLRe+hZ)Ljb>}`qzy#~g>TTfGWxWBt-!)UcRwAR zo@nvlXs|cI-X76wZ6PokPLH3LfbBlMEx4=vMc-jX*#K$%Gg)%~w=1|@rQVK|34oe7 zBoFo;AGU%}?sA`&8$1*ovY}92$69!_&Gt@s^oeO!-uiFdbbaFE)b zZpmqa1_9P_gK`1iP(aK@N($wVhu9FMLUY4mf}UsA$jArHDpMR-m{-op{oS3qREaN% zKK7Ga^;S=TN677e*p9ZzBx1XJ(`xg8@y)$Gqc-0|{Jh5sK6g>18MxcWfs6a<>zJO+ zF0k-xf&mD#+}uUx@#(Z#IqpCx7Dyg-cz!{u8_TEnR6ff8?{$OR{D-J$Bc2=k^Q9Pf zh7Cq_|6MMdVcfMF$pz|)k7=~3yX>jHX7(%M@gKuH8kCmc0_q>=j2g}U)F`ih%InJ$ zLF2XEGy3j<_C7++2fweUC>*$^Kfe!pZ+VW`@-dfx$*DiT^hm(2p&Wg!(eu=ae-x@OQqPc%C?01xpr3xjr&kSc z;=9aQADy7_k?7zSM+Pb-1{d&Swc8oQxjjso*Mu3+JoLtS|V>EEE!>)^Cv@!jaRUL~o zeO-6i717+PJ%QA>p9cnT&VqVUtIe^ltp!U2yD&^~cJ1_zlIX{v_pbS_@fiMhX& z;Vahs#VP4Z@y_!ix!Jv}e7RIWvNb0|N+ga$OCD4NB$7WM^(SZrYwgv};Ytw2qtIHC z9Mnnk=rVhOaQ^NGDALO<0g>56o)QgxMA~J|8%Z0tSUQ!m_to0F_TipO zHR8zqNqmrc+FOxj=r>^?2E$zOcZ=Q+q94VdxiD)UK;(%q)7GCZ-35e4rQsw%q~hP~N021DSr^!kFK)v|{WmR=pQ%WftLV5J3dZtpnu%zgH_ zmcH|zlkJ90%y@fHm@muKx0shj0O|^w?Y|t+E?w~PH@L1OLP1-TXH?MAKX@b!yEkx% zd?K_5ci4=n9)pmz@$A-lK!COXO?Z0u^&w7Ht+Z9jWBR)$=Z=kvP9cqoM6$8ufRgvc{95Cp{(QF<4O-2jr)(`_`9UH?auLtW z0mf!n43u5t^`m0Sa5Y=LzaGuE8rQsRTigO4%Z- zcEOXF(w5d=F$~UF_3<)YMbJ z+$+4BL3Phv5Sb9#rC1ENJ-iY0D9u6ibVbGBcyaadBch9vR`uarwOrjWtcm`7b(Y79 z;CbaY&Ceau{yT5p&sksPvGIw$hk?MBcgJwAjrib>|BFw~e5lj4MvdY2uB=V%A$#QI z=gu+J##U-An4gGZbHc28%SW;qB~9yp4lV`V+9u1${?A*ZB{CJ%>Qw-bpa&fxnMSs3 zXAhD?CE0eBqg8A1O%+5|Ob*H&h^NG_=dct3F)>-d0ekwn7SyFd3pP_N_(BXk(-u7x z$n)aQ?gl8JF<@UA@t5$r<|}*^pU3lQ+P^6_Eu%geQMWDf>r>j2%}9nz*xK|dU;l~< ze3PG2tbI>ZF6417Uv9zxWracqxt3v;c#Im0(Mo2Igtsp-GHU!UpFYc|)mLmuFYzE| zlU%F`yr>yZ*sWpIZu&0L;)*W)f=)9;`IJn-%P_+_b&47aG+18Y`+Jrrsc+ome}27u zJA+SkHJHkX%wat~sNV>C2_NQbl}#5L@?+l`p$-{DxSw#CzsO8r?zI3cP6x|ScCH|B zSblS3u!gH;~-_RnkYsi3HOwFVS`F;w6PM5cD4NsjqBw6$8h0}%4kROwo?ZO z`n>3t=>9rJer%DFGI&*s06T==MMHKdB9VoIYc@6ovFp3Rey!1<2` zB0P+dh)DBY7xs?4PnFSIRBKG{d<`c=0PA=izgWF{VeBsLuDVit$Q$Y8uU(KvZEg3N zT8ZxSpQIE{Vs66^5Wln_v0BISKaOYMguO1uhJA&|3fg@!f%Dw1T{D;i8haIYo{yFO z%)0p$0SnGq^VHc}LRAOa%~s?^XP}i7uv=X(qeGwiBn)?bI!U8yxK*~S01lUIRMj%} zOODS!E4G{}VJBuk_IoVW@V8>a3W+NnzSN<{N<*_yejdz>)MC?2ppbdR*+AIgV+`tQfilxospO4-It}zK=OcRiYLTsZg(? z^ayWgt+(Gh>8iqhh>u4sbo(lEb3Q$q3?tQ7F5pp(iW5R)wL?8Ohckj}nKj<>rSagt zoCWY!7B$fDmdhjx<*Eb}S23Stm1CA`lw+hQSB`DEL|ZfZWC)5H6AHM+9nLx4921ec zi;D>!I)>|B$1#+WILl*K>kK^gwOHxt+;(YuH4hBATgf*I?4V%+8=Tvej&w{(3^jz&WBfDzn z?FZ0sahp(6N&CD1bb{(f`9FIWL4!q4X~JYOD)g!6ZMd{%BeU=PyU$b`gH4XNJS6_g z&G~18wad1<$U$uD56|8MCWdd(=^N_G?#Dnmop%ImCaV^CblyM-?}bmPOD{IM!rva= zpLA1?&KXc&vEg?H%)UP&I!NEwMbu-TqL)$}U=|E0&W%PxK@}1_=al*LfHKEQ&D~kc z!v||t$o=Ly=>D(DB$WpCl5VpwQXEH$6q*2jc{ z;2a1FsusFmYZIGQ#M{h{`O>NM$;qXBTzO`scyV>iQmoB`rCJgn0SCYQ-bMBmpW!!T zuzQ#bhxqom>!(!Ic(%AWD#k&-olaS($dlYwpBYIVvF*pRaT?94LUPsO*g&9{5av!@ zANNMFJC)+9R-{MNifnk++wr*AEu!JyjCeiDt-3zmb0y8yR`j$=?oFxwJ!+-inVV^x z4rE|BVa34_aM;`m0X zn~1FtfmO%#1o`{k5091h?9$QSu&`<2m zhVOzefHAIzSzRFo9?YR+jp#L?^GZj!SG_i^8+WHJXfF)ft2Y0>Np2jBV$nS@b&o3#fI3ER;G^yc z&PZ9)0O0Aj4Ur|cb9np#3RQ$eS&{JQ^Zv^YRh{_^KOPkK+zOW)2ky{wJx_u>`p4x* zsxJgnMMjTzxN#EOOU>=XE*0_cL1z%pSM8&xCc_uT&up}j$+!eB;IG3QUcGQWHAcmH zo_T=}X5K`+H8pp$x8B&y}Z$F_VOuu|-iCJ(+hilgqz_)}96| zUCXF}kn5XykvYobmyZ%wmk>mtLfpn4$S-)B)usI$zC2Knf^oONdCVY@?mBRtRsCQu z{DO~ykD6hoZ<=rY+*$PZR1s4FsWK&tt%ud5;}e-oIPnnWq>#x%qXJK)>!_&lrS`>` znw@7yhH73p^7oR;;-tciL-1u7$+ZP#lFX8misiqWC1ls{25v@=ZstG!V41r}e5g@2 zv_vyFI^3~hsTZJ-J&sqcRNB;#HHhr^DwFw>X_q&meT6&*FFGKM@+E_2^rj${tX_ja zP^;vGlOVD^_Lc87IovXT`~7B!0JUlKQU2Fyy-m$;KK%@{b|>ff_H5)R-9O{$^^hm6 z6aa_~G{)P(7Fg-Gf=dW3sE2O0&3x|1lDnMFa0RR>jn;bKT`Qm7g8f!^CK!r@`U1=Z zrC`0wKS^ORP(B-IK;Xbd5OIdUPGXcX7UJd`A}nX~vOxWgOjGFjHvdQws7+6@(1f7c z6jy3tO=>*Bcm2|hJ$@LG@;(WkYX@X$?~Vu$@%@TLrah;L+3!=WCLaQqSc$RQhWq>g z*Mke=`z5k1Vts%I3HPo4JL?C79}o7hmmGltI*8jOK3D&!-k(G*q(De?eI?XFTF+_O z?iX4&v^wWsukgVnZ@JM$_{%+=Y75CktAtX*Ez|wx~zJrgF#<&g>~)m z2v2_`D_eoQ@*lzfTLHJj;ZE18R9uZI{Bb2;1%D^|Dd~cu_cMdlaSVHMYkpmqptw)dSgyV?wVq5m|Z$6a}Wzo5@A4Q=& z;z@>}n55Pt*X**vGANH!zz1i+y@>pI@|PC3Tt%(QTLi~_zK~i`J&9r6-|v=(ss%Th zwNsVP3#~k0RJH%peTeOJ$*fuX$gWVgakx3?@>MiUw_VbI1r)izJ4;^5X*Jw8KZnG` zQ!F3+oh@OXM)QrV5)Pk@>W8=82~joc>0jh0PnA+?pP2F5V%6ZOQ(no-;F$g&e;L`X zr&XI-dMEt!S2rwXLJo^J1w*5gE+_FvGIJNi{j|d{rG?7M?Mny=N7?j}@@1h5SgzJz z7kMDC7v!**j;TRxmNES1M0PcQNg%R{^{|?eaDYw~$QxESNI>s&N=)&J?2FlmuVvca z$%CfTVQ*3Ih+1{o|E)Bm@0U9W)|x0(rM7dhEvNy2l3PrYzTcC6gq${#e7+Ss6zY-q z)AgQg(oqzM3M$20LetxQn|g)rlgY4xt*=Bi;nf~uyLMa2Z2NQuxZ}@>S&*$j;-MwEMEDqJ134DT=)YKQQluA}h9PQHC!I z0ZqU=GPvctcCFSrd{N=(DOYbd9{xt*L$AMbYYK>`o|$s@ZsG&=zHUIbj@soSqsnE0*D>yH%~glT(rvd-nBjVC!$6#lFFuhrJ>l?SYO7*$668X4u` zV|cs7El?&S-}s=-n(_w;* znoPl?Fl1+@LGQ+8K9-N1P;y|PBq(*; zKWSAI?F(uRF(*d8^PHb?#rFQ5U|doJSeN|V-pE7?so{w&vGd|B?>F)p^tz+LE~Vt) z++}u-n%AZi+37TdThuz8u~1eVtz5a`6UXkz*H{rv1e9qis|ID5_#Pd=F=;jS%{>m8 zdjIQGv4A%6t#+f3Z|WY$rXWyzRLeB9c6#52=PS-XkEVW=DILelk@qJu7*ZF8>;<)N z9sNZE_BCNH#JTdzWJkL;a6L_yZc4Scw=*1uB~UA*M>a~5B-aWG+q;Qejjbd@USbs8 zON9NyD?Ru1e|}XrwU5y%2?nIFaobQrI6IRcHQ=>4lvyFPgE`9om}LBSBl>tM;@~Pr z#0P9Qc4q|y_VoZJIXg2uz8WgDiy)XCefvFGq+41obJ3vI@qoMm1()j_!W9T=qdeRz zXK%Bm7W~bDn2ghROv{d`RLo27zyy&h0cp^o;^zgZHpX&ghEF^}6V%_Sf?W+$8I6ae zDNPvGoqTQhO-6M=hgEQ>-a_w>B%e5p`|+HRHExK;5nKFdv0lh%Fe(KpJVS>5{$0`I z%&f{}F=xSJ(hq(3OEeconb@+vYuaraeqs7cf5q*mhO}rmex4cS3i8!)YY# z)3hk(u~w6=Pm0{3RQ=(RdsW*TB)qoU3Px_7yi&`4wVF<(t?fG^BTPenF_*do#J#3_ zf8+G(6`b8RH=0|8Zn-lmKT%&-nTdMcpR1isc6@QUybqnfQY& z46)qoI7$h9nx`sn*n3pD&r1*MW;^3OlIi1D7Ojx45)_ZxY+5pmmx0; z`6$rd)P5;Falg=-k+!W1Szz9U1Sa}fc5Im4$zI%D+mm?R9S8cn#zp`b<^LK?{J-t( zqx+rw(i;mBHGw4S?zg#Cq6nt3%IXh8BItD*-XO9n^(u)xIwu*k#!5u0JdE&Q_Q&b(YqTj?NO*GX(cnDA^3`7r zdY3g?$5!mTNvpJ1mbH@C&C;<&!Wfzk`XWUaS#lBNXF!@VUF!(buK43^3v%mp)9a+I zWbR2AEs2e?J3nJ0cqUivxO_nNlLFHucJ)^0Jw+Ju0J6|#s?nmQej)5{htkEPu zfBuqAGujn1;~kiK*`~p7r=L8*qY||MG>y3O4`HZywCx9SCyTkn8H!lmiOL;~r%&h# zE%l1Ejp&rJ8RF>l0s#0mj|kg47s6|VbCjcAbfN<0YP)a05ObXDNOOiesz00x4h!bR zr`?=*9#hFiJvSd#H5%cmUnrrKV=In`@=C0SnH4dMu^ zChBZmbX+n7r?ia?m4iqH2+el+c!7V&(t5nH}X9EXn zlzm_coDd)mRo!+mE;=P5{E`hYpBQPx6_Q%*x%fM|Y})<}KD8xxug!KMYgmd-I~%=V zy#1!SU)1YD+r_l4uD-#^`)I2Z$c=P(S2K_eqr zzA75eHCk2sY5698tvE!q;D-3Ik?nB&IS_@9WWlm!LKeYMKM@t?%#g~6H8K$sbe)I7K8{{Krn|#;q zx_PM)+zC-3sP`gT86BC=PEA3W>e*52ql6ygC#FD55{gy4?WvZK=Df#uFzbscN#R38Kxj$; z9DSwkki4DC zJd@fH_DwdVkO3VL>Hch7YLM4<_1b<@uuQ`9;XXAjbg!S!p|Hou=+9Q}?PcIAOG8Y{ zxe4FhDaUdCbd`_bPy}0tTkjRC!v|-)eVm$BX=CbBs13gAi8qfHE(n>GNv?E`rL}+F zTanOdaLNNQ591dH^JajL_1SQ{&E~{&hzQ?VPy`jg{{ziQQ|NH1Wc9Nu-k>3ffMV_c zqZ|l9q~2M$sR5RVI_!>ohK5F2q8WboB%2vZzLC#7-)?8C(`Kf*?iFIhJ+?${WtWcxfb@rK=a$Q&M|1aVlzWwa9!Yend;q1*x$ z1UekZbl2x{O2Xf?)Et+c3V+`_nD;&D=SVp&*LAA*onGAzOTdx~*X-g%-aL&=O{(-Y z`9r;E2F~5LCrgEjdt`C);FWNI^ZFAd6AOT?yL_(sA}X(tFvjwRrDE`{M&r8iay#st z9M_*!RO1DC@at1N2abJxR1m7+0LOgawH!D&cfQ88{C(JHfvC={CKrY-1ynK~N4)=s zu(OVfGVR+w(hZ7&bg6`dN=b`=10r40C?H)!!wd+BfRr@S-61U_K-SD2X z_jB*=bKm=X-u-X);|g=lb)DCF9>3%G9^@B6Xzu}4Ooe*ojPi`qR`l6IwdK6`w8y+p z!dsnbDm*UaeEpZ_1QcUA!IY|{^$ICs_XUM1GODZ#B63W%x)TI2fOX`0&}BX=HBWW6 zNk%(mx*A70l*U{uQ{0vGnn{$6;DSp}45kYp0bzyK7Vs)SdGm^_5;glhQyIUBHEgQ) z?4H(`a~8?~0Z-aJnjh7v3e}X4N2Ec0+^N8+64)C zoj7d>nTeo|c|+ za55UDxs6@nwy2Z%$L0=dHfoX-Q?0o|xUB+<18Ocjl15`nJBpr*uwSWs4hT&~inI;uFFFzMaGT9otM zAuhcuelCW$rJX?@oBJ%H3?oqfrwVkwV z<5d_8bQ2?W9juqMZM<%|3>|}l0+IZcwWBUuLvWx%F?9c9m0QBbe3Rpu(bYTaYv6%` z%L`icfwD!=d@Tnyaf71GcL`tvjmNn8D#M}p!o?g_PKJ?4<1}C-e+D_Cg`O_6dBs7bauE2Y8dVPjY-_bwg zbk6E>^<1sDJK3E$p>^H%vnS3z=UoDnX^9FjTC(tAG-TpHoL9%#emkuD0_A?DJo z8Wh*u<>@{Zeo#x4nEYH!pEo!b9p!Ek@HTr3Z^Jk~Q zV&{;VoNdVmDmCnUovJlg5;i~?@r~iqA%{cA9lU3#1Z-$}xOHPk;6FYFHd4#KSm=*i zl$iHC=Yvcz?}%pB+b8WK&IfXpi9f(j@)N;KXP4JjAI=V@FmPaPiemaP4z|(;_V>IZ zAFODV6--P1&QZAJH0g?nmloga%XxW7)C0Ykt}w@1xw5)fZT==a42R$=ajLw>ITP4B zJldG5#EwN-F8BA13?>Ai2S#tF%1u3#zkf72}-g%MW;5-SBs8b4{_Df^@jb z$Kjvb^cSXw773KsGsL35ce{wp9ZkA1v5zK^pV+8vZswQ|ihGT|kImf|$mbd>a4JnI zCTiHx)@1<~SXs0f%RD%WY(t5UZ?f8i`u-@%S^pmMiS?BV$BsNKU>nsXY_ozEI6 z_DRyDILYSS8pRT#QRlVR5}KX)F%8fw{Xns|Z@D&T-rlWOn+_&&9c#VJ0`f!SpGLrc zAD_jy6Tj`V5QvcU$EfAS-&fClD*<%9r`>na^)wZMOT@(``{yKzh+VOcbmQV7KiMQn z%o4%ES50~#R`J$_6_M_*>ry!U+O7HgBWggUj4Zu*lAFMOz})Mzi9dhRmes6+Ma@o zaJQYDZl1P`-G$p9=NYD(zZ%$Fn0x;+noUu|Sz)9euIPEGYw!%;hYc+-81F{GScQ@7 zt-DDII6l}WhReY#9F7cuwM5CyCUHo&&C-Xu$DPpzof@Z66~w?s{`($7cvKffSw zV)WN`{{7v=hDc|laURS89uQdKa6vv{cQPe%f9p#v{8&U*bU+ZaQNB03xjp)+hq`h* zU9R8H%|r?NYtocyeW~x0O#f-}%Xdntdkw)YVo}UlNkaYD*kc(}x$@=FR|W7Fj%?kt zQJX+{tLaax&i%AE8+zM`O$8=-zgsO`WrcmuchWyby+Ff$sxCi986LtJXI2OPb+E{c z+u->Ev(LvY+NGcQJPh?O-zN=7Zxw# z1`izvw_@G(yjNcmInH;T(H_jhPwa5PgXw=vR3qkSW=)s)wVJ#8mbmqlEhzrZo=E{; zXuzI-T*uC2y_+;$+g)+66qtuw89J)!-=Mc3- zqz>Ehy)r`BQ8qnJh1q74qELFDIGsopTHh$ zlDueGc`qhBYW;Hs2zx{F3n;083uEI_{47|2MERqe-_eKJMd(cbNJY?w1LDevRn2Yt zS<0@6nzkFc>=$;voL_|&>IwNe+C#oLBSgxe? zq!jbuq!BD&br4^YC!%p6wS1}&rWfS?bcEt0z~{#dK3}x|OR4ZTqL`;>D<{CB6#}Ip zSuUHvg)O&qNYc>3)ZIuP85PQGa{pq?+4BCZ)+2`V+o8Wp_+kMsEtQ^#12-EpUGk=E<7OLY%zE4c<;qF1 z1Z6V=@3?xXW#%VI%1~RG2T{zQ$iy>fS|PN#t;cCo*jFW0H|lwfsn)mn zKwPa|MT33J)eVHa&S~wf^YyoJ>O`*nQgMXqDsF9@RNljs!aL;fO7J&NnKf({D-s z1{Hx(p6AwtBwP&Q;@yw&c0Sz+aWuEInWf4+;G?iLHP!sE0=L2vJDW)J#fpvQN=kCr z&!A&E6?V$+TS-nfSsN_~1m`wvVkPXFCKp?31%z+^-L2en8JV{ak(Sz%1MR*D-mu;< z@2&iiLV4ln9s5L8Z9`J|q7r;)q6bct$Lpw5zxkC-%02>6HdiV4do-%3MKOs6@n$}2+Y?bPP+six`T7#> z*=>Ri*Ej-&Ip8~(5w@qELF67hS>q|TW)=9oZ=mdS=MlZXeah~awPQ+*2do{3;8{1J zx1cWFaLCn9iS~Rmi@%bbU!{XVr`Dz;V|kRsBu8CG@?v2rL`rI*|8=QO_4UNpr4u60 z;#*)OO!41C6nfXE+`tA8CL|x2KUQu$b1xA1@zLaCcvY@1j_0B2%(ta>N`Y>fF5iT= zm2`BkkUSsIgYZ_`wP!;&SxwHY-x$RGB!A1eF*=@0?LHD@vB{bA?K0v%8#am3$128C zMlpo#)70@R9sRH)1_2~m<|iUXH;^5&hq<}AWCO&$(zy4MQ%4@y-D2Eh(%jYPMveUT zX!j+bj#|HzmWxIN=)5`zUfMDOFYH{>U-!E;R&PJ;G@8$K(zF<;$50dr%6(ej-f$nu zl=E9+c`Wx!kNH}Zv|3LM7fDPWI=!_K16ufbXI+z-97C_tRJr=borikK^l_u}=MK-# zmk=dO-XG3-r}ibQHAE#yf0ES8^V+qF*7R^}B(JFCFm1A@k9c zTum2y1cFa%2KHuI-d3DHesv#5Op0Hn;h7Nl1G1+{=}fEQ*w7Y96=taCiJgb9lV-^g z;x@loIj{!BoaHw|@{`SnXYkf-lqk+6Z;NgS2{w?e)03T;4|_r=xQ_-$fzP1bVS@&A zsS~?9(IR*AS~p4WcwNDEUK7AF2~;-ka3%UNpPBX-_ZWHw9Cc9Rewl=3L^bZfG7Vyw8)bi=)@%>&)J!v)$+$JwPutK7|$EwDL2(-#{xA@la_N$UWu#> z=JG*^naZ>*g(U`X@=_R@4-qo2tC-{Rr=RXw&RS5aY)m{IT`}Xk2-Ym!jlrK=d)6I5 zPJ4zlB-5X5r)G`|y0Okt_^yhAgB|X8VYZ3Gv z(a=W8GFw-}#yi{6v)GDi+g;nN$J!rTLUI{*6l+oC{Gu$CGh}l?ISH8NNS?0K|!fuc@1dJ50Y6Y$OXmI|p<89QS zZK-H6G1%gr<}Jnw?1Z6^A@*Tc-CvA zY64D~BVXT0%4;#;qDo`__uQA>#jZSH&11PkA52wQ##%p=1>EM>#Pj#hY3>ol(SG@QlzyOUHwBLl81$?{MKj8{w#2daMo9MrqVwz@;+ZzA+xJ=JZ>3k&Tg zk6GT(4u`=wzKj(WJXA{)zosdfxoH7rFbk`_HxjSue$~7#Ep%L#fq=klR zX>X6cC$g8x=Mn&}Io88Nv8P?#V@z(Aj2YBb;gMjY@d;f!V0q@L2)Y`uo_}ucNX1D1 z9X`Y&7c=5`@+f^EV~kNgEX(A^Twg1bI8e-UUlUvi*k&Vl{L7x0KnEH;l;JHqZiqgH zPXTKZ)iy-SmkB<=0*h6otv*UCnd%<$#CUV9Sh#P4y@Phu4YzLpw1XSkuq6Kt2*RJ* z6w?>vWqvZWsvkL~_Py)@C>sf= zZ)o@esCC02-^**_&9DZB`Tw!&ooV@?B~ws3wWBvhu$&L!-CBLNr3>nvTE+;n74y~>FjoXD!~-*z2H{Aws#!*5ocus}vq;mg9gtR|KdoPG_8=6|)O zmJY8sx9E4zrc@=$vwo&C9V--yVw6;yqLwksY^3CA5A+jc8fZFw!2TTUb}ZdN(34;@ zS+wXWI{iBI!7ID$0?qTmP}(`QMi^JjB`_f+U#oee4rMv@T@m+*IQ2HVdiA`zKE8KGjVgkLo3 zpu0VPw-lH~hF(u+v$H6@Kei)4dh1+K{1@H@sb98%0VyUU*S(l#956h|#3I;G4QJAN z-6)wX`C;jrbZD|HE6W?hatAeFpx8dX8Q3d&tM6rEes86w-XJGPu{s&U|5)cW*0Ip8_;2NaLCfq-u-Ub4@)@ zkP-ZF4SEtjfP-ttVMIc+`2GQBP8`UI-iXSq#$#_*$xhg-E9&&v zSkwnEzL(vMbA2WJ#b%yP%5sc1tr2eB*^z_qw65a2`ZKR5{C8a2m@D-%V!pbBlZehL zXQbq3WHpz;_K!Us@mR5`B;Kx&2a3)-ajeIOn}HQj6C)~tKJfTkW)c>FY7M1 zXE(o_1d;Qp9Ua?j->7$be8X_g0g zEXa&zU0%<{W3$OVQYs!7qL9Rz#88NrEq-gq|KWp-9W2*S2?~Ytj(e+;TnD}k+Vvjy z%Hf)Pi3)be=LcGYv9|P_-WjMfkQ4mzahE^P4~#%jg|9-6i#Wil!_Y>jlT%wUC9dm` z#DM!;SJn!+?&N`Whu{xe$v=57WAo&yO9#fZDcliW%cJ=OqlH^9ASD<1S~v&PJV6`0 zyMrt9?aMKO`^!1(d|R&2nc*-pu}X*)%38O=sq`V^W91lu52?rJPnO@)9O5@Y8Sbx7 z;LZS6y8l5N{Dbiudaz+zasAV%*QqmnN4JR*&|_NGohmla>d9ds-wgX6s73`+0idnH zVfY2vZ4cm=JHF|8T?w^5^={q1%BrFJjo%;*4%MhBacvn9PM^vW|Lm#mq|>i#iOaU- z0YCb@QbmFIuZF&>XD4Vi$A^d^(9s*92x3@xpxL`6>Ywe$O*Ex`q5R zWl1eSx~7b!uel&7nx#nlV&nk=wo^2&;kK^3JP+`7Rw&x73unmQJ+cS3=?=`sgfQLA zn$4rZ3nHASws}{WNzeBT*ZW9cMskVD>sM$wh)&SD2i0pkWn)p3?Dcm#==>N8-Mhp7 z0(givS7RPw+0jt2s`v;UP^Q)BlVY|2km4U!%YQLL{tUDJ=@|(#@F@|`0j3IzVi1J0 z1u+b*iKj}y{7`GOkiV*~Eh4iPf_Yl68y8i@N)J+k3~ z7;o;#$xLxf(n+Dhrt-SqlpRE$Uak=}*|+XLXBA%}iuql$rbhn_X|d-tBbnz9^_3YVs9p4->!2oqX|U?&nLDm2l8 zUa>TkN{Q0zG|v2>)In94Wo=e-jRJnN9wrRPU11km-egpIvs`0qQ3h@`3`a@<_9_ME z6g!DaSKtKh1&Ds5@_8J^VeB1eZGP0OlG#7ia!N^h^~*H{NH8;xx<%7?-=3*};Km*6 zr>-$!_Lo(U1lmA=+iYg0@@0dG2qg!0ot>wl4xtSt3I2je+hbb0RlMt9eqg7|_-%AQ z1SB%%rCO-(zs|Xj+*SH^JR%yuRu}#eL?|2_;aBwn3cx>?<#Z#5ZyXOSLa0DKuu}eu zM)X$#GC=@riO8G)br}$tJEx}38b%7WB0+CN#^0}fy(>WuW*~{T*GX#_Ykbg7_w0TzT1Ufk=+}=zjNI3veyCMQX?Z@x!qD3CATgCS0CpMmYWvI!;86*C6Y0j# z{CZ*OHJzyCeUtz;uU+bLoDPk)L_V8xUzr)K#fA}r7k~&d_5XA41GtKyprEpn66y6d z{1r&9V-wT-{R!|Ep%-#f_Q8iqEdyG2D94s=SDpQT>YxkZ1OQa+Z#e4WERpI0L~Kye}*HlGU2G%COw-&Ja3 zq}PPnOZrCJc}126~D=2IVcSfzE@D&4V8rz1J;9W16Vx; zhf2h1iFmVv(866RQOi3fJ>dyqPBaBicTgQE;3b*j@(n1yqMXfPS^+E^s$O zhBfPjV;(OUZ|cTo39cr@HNtS3*q(sAkf#GCg7wUMiJD9Xbb*B6^zXfw*eu2nbh>@k z#Jo(UUiOvI!$r{sB>AjbrrCw%&3@@ikVb&|K)(;580}wpkw25$0=5hYMr4V81JxzP zsQzky3W!r-{7>Q+>*hx1W>FL_He z@nz-^zp-fMy$|12LHLFgmSM8q+`&RY&esiX0fZSs0rUBxnAjX1KO1v z^N5gZk8uq2_gj@!kf_gnUKuZvn%Nj$CVC=d(i!*V+`mjneo6^grv&!fo;!V) zU42E2eo{I2wdxO95#J&4q)r~BuInsQ6ua+Dz^PZ2g zpi9y>=}CuGjnIM%5v}sjjjD?(oChZDrN330*c1~BSAPm%TNB+C@K^n1CFuU8=ZqDh zzWe0PQ-9HP#6$J!#lX}Mhs}aD0+`fq0bqg$Z9_!~GTKRHrST- zCP-tg!SM%$};=dUCG;d)Cp9Oq?iZ(s1sYhDZu<{W6B0to-7AMYdWJ z)>40XL$|->dk{{0Xd`3+qeA`bYuV)C8|n0AjUYzDv2$Yxq9r^QSlMj*dpNpm<>z;{ z^5AnnH+F!Apvnj#!s$oqJWkLVGYrOjumcom)VaL-r;x|6kXh$2Op{O%T$En!d?jl1vn?Fw*S&Ls1UH7 z4+5`qQ-%7YR_CDr-qD=E!0n34oL@H|{?vk_EAqa;zIs@u@@b^ybaP{3;8kyo`PB$;@&3T-@AArTKJe~ag zq<%P`8P^B-_|JWBi|7|z*di*8186z1nGcW#DcY|}S}E>Rdp;G3OyuZkd$~ZeXFqJk zT;mJU!|kQUC?E;OBdvFUG{tt|`N}&icNRpuK(Nx9Z(aNye~^YC$Q4VuI)JB0+7nI;ebn6{793 zSgl~E+pAleppvB^3BrRb`-F(WvLr^4T)sCg*m^1C)}k+g)rC10oAYGrwvz((@;JSS z{SDBb?$=LA*t~c*rPlc29d`YAmR7#xHs_XhUy&|{lyDyKin{(5^3|gRgbeSGr0vLT z*VP(CAL8^OX>Ptb7PIEUmGK}P1L^xx2L)m@wCe*|DG4>TK4uA0F;rLff9;nd;+qw1 zLr`fu9TZ`xl_eNtcu=DBk8L2 zevLG5c2?JWF^GXT2?Hxm0DWKCwQ}PX{DlHSKn)oqcWv*$tGa8bq6_xQ+6~9UL$YrM zFjA($$qIP?BuL--{?if*!e!t>c7YZ2dHs!bVn#uuA6$J7VHKijFTziKNGa@KZ*Hv| zH9*=@&ldtKgb(;hTp6WDrrb7(KaL z;gd)&>_X(`?y?%C2F|4!@5{pgeH=RmWSk&iOSr^83cWJ|QSiw8oi|=c+a&s4HldW5 z?AbBBa009vb7KQ%-nB0;KfY>H7GzU8b<8~$vnAsPkI_iN^>9J}u1D|0Wi;Q25c}Z4 zsm(7pw1fGtH!&qnP-UwBa9XvU``TR1A=%(@oE=EU(ikh`v@tMHWdo?NtAV&M9<(y0 zq}O9nf{u$UWnb+xe@;T}MvyHIP(s{nl0I%YW62Nyjo-qTpS#rx+r#(ig%pj-=`lvm zN++=4xq$xy-h;98N`v_sKKzg4yz!jFs|^Z5ftFzPf1E1a_K#%^row@~r#Q9G?hPSLONS>SvO-WTupcV3K1xU=7jK zY(3V*d|){Tj_>apxNl^N45>3xcrvFHR~Vl^R+#sV5^?R6+DHN!pA7H@Q7O4O{QAfU zeLbwpQ-btE7#QTs;DT%QM+Neqiqu7BM?*toXR!s|*-9rz@8RgYiV@`j8m zx}>jgU!5cZV{HDL%~x{Hn7e2(8V%fdDufaPn&tWO8b{kA5)}@Y@0M35BTxomK-ud< zfX&*spUjN7&+EbQ<{y73z%4HWg@MO#_G);fOttBFwV51qvBy`C-cI4;{Pp>;%F?|@ zuDOH_=M(^3kfO1Tm$j$Pftn6haIUcfs6$Jnj-@pi1|bFi`Q$1N^2*|FAgD%&TX#-D zTZ_zSS&j#9(b5(WZ!J0kNFne)lWP9+y_0ePfQ=$Rn!)w?`~iHUxX+)X5~BZf_5S@q z7?xKFrpO)rnCN6T2*6?mHg7%*_wN1k_D<0q)Ckg{)~GQYsl9tqod!jfK$BR6gU^D= z$oS9qkmnHSklg#@+u>q}pqXi4U7JD$&lqrbBtic$E*`k8tv#>dgh|5V3BdJvDAAX) zBWXMLYRrlmq|N^Gn8^a#cv(oK77}ipGtmtV$Tr?~M=1X1Uw3gityF0t-PPNB*6>tF zTPd0yYwbsnJ=j=)B>I2dN&j;#z|D3KunQzeZ{50iGG#S86(Qtg0RaW!aBjfn&(N;4 z7$`S2;+sY#ZvRzd{TG%_7E~>Cf%5?PRI(uE^{-1<35<>YF`!r`sM(9;-;~!s6`Q}V zi=EObhrgoUa~2y}eA>T%2bF;TFYtf=!aRl^NWLWo4=I2|^ZC;fd=*4dFm6GX`JVU(#WU;|VtuPj8a{ zV+`Sb_7gvc;h3(ZwRLav1AdjdM#DMOm+$O9$CTqPzYfxxsF*54J^1jbPu$~-IS9%T zF_{4_EYlfyGv+BRxk16O#p|Kw(sEvK;ewM(gO3vHi`;(VJqLi%zbQ82=E&*6N!~nv zmYPW&LqkT=`Pw`p{`@g6)4kYE_=J#CVE%6(g>XIjX4p&ot-!g&Xa*+@(&h*2v}Jo$R&}@>Z#4yKb^G%x#WeuDe4o#b|Lb}IPNMpRKsAdSU#_J1 z1yb_B;BXc_9I%M-pp^v@VMp?VR+5i^Fqv>8yjz|r9m$+hKdK9!Pc$Z=Sb(eqrQz0s zLXR^xbyU~12>4NW1el)F&RgrCzhY;lJ%n0qxEq9Z7~&|w6Zu!DxHq9m@l2&Z`>4YG zaAU2>>?cZsAQMHOQl3wT++2XC=1!1~0mN1<&cNHHHdtvf^Wr`z5G*)`HH z#8*NqVcVCl8l2`xf8pR>{JQ^A1>m0Ng8cn)R(dtT^ZMUE6w%_4=UMd05x8*InsSex zz|VN8#1!+*#HWx;zPamlSz?oh|yt<(mT34TBXq)L#J`xA(-r|EawN={t-c`pxHA z`{XMKWJrsgX_ga7$Pn6j*#V<|#r_GA5cHIyR|str!~(mVD#ut*jO@RwQruzvIq$ee zS;0SN-1!Z`bbJxn$L5)nFRUaguD3+V)KttW$FmncQ zr0RMBq72!<`TQfGwWBf{$fEUPpso}(2_twwOmOjTE6RbNV5KuD%sJ^BWk%o8XG^tj zuh~!`{ZZ>F4RE`_(EmL)o4=@O@IW6et-dENF76H>iw6e$7A;Qix}&;AvKu)YJ{d`g zV0!j(P_lYtJB}2U(q2;3v>9G{;UT{m$r0P;u4Nrxr>_3VT8X&;7fSA-UO04wc~F2lK)C$K|=>0p`4xqjW;fhc2^K9ky2z<>SBaHz7SLST48#uq?`* zDCMQY*x7KP4!6@G0|}UMNrALO>fB4=%NPAj^S$1QbC4no1dgURHyiQfpIj`d$)0FEPO_KXb7|4Kuvv7;966l4TX1d=q^xocqXl#jw zlFtDPmEi^YyA1=9vFb9)!Rhx5--yG6G3ZldEE2a{ojuJMnZ5~40%d34!!PBk=rhEa zbB0p`3C#AxgRn8)-|XhsiQ0Dnfuor*)cB|);{O}6y4vNH6FZfPvNqX@0YdjTN+X>ze#gNovp zQY;FIsdEh;Dj5D2jz%5dj%}!Q7?2=LHDAmW%^np*hx3Z>^)*<_)#@x{q2=sy>%-Yk zNKdW_k`x(xum@&t$eUSkD^Bs2VqChKeJrLgQQ*qN*!LJ*;WS$FmmD@fjN|8(&#QJ* zft+nkSm_DdGRF?>boYC_b6SdecJ~o(+<4HH$YTRdoCSn0f%`CFR^MKD(YF%K>aeT^ z2X|Ju7U}HREgKI+aPiETk3=sUboP-u?Y8AWOde{9!fm>a2iTP{n4dZ+rZq85t)yl9 z`QYjooCu;2J?$Sa7j(2HhO#MdfbBN@yREi{SLBa?k}2}J=8bGs`v5La@|UR z4ej#8M2#h?5q)_W{?)q~GG~QD!p-GSIE{k7WcYMngHRbT(2GNp0R2_fyY)vN04^AV z1fzmeLIi*ZnSeHNZ714ha}gz5L|_7nZ-x@OL104FT0pTonnfJsS-X8PbID*!SaPy5 z5Fl5g&eqe8fWpwNUYyo*NHqDnDgrCIL_2bW_lQwA_ACnYzitRx;V0D}f7*l*qd;pC zcTUtTrj$XvDmOk_6p&Q}2A}lRQB^67d^KUof2-B=Y@uJLDP<4H8qo#Q5ecyZT2nPj zp(3ZR2PA)G%z@M*padq4x%8;v)liB>1H`!J<2SnezE5HG0H!cZel8AVg7tRIp(8<--vTKu2OOkP49aCoyS@|uS6 zV7U9mAr{IlGg@84jZgSoN>lNF>_@2oNOy#Lj5N3Qd-HUa>Ata8w2%m)EqD}{D4;n; zI5JcubZHNx8?UQ&xizWIDY5ctb!Fx{geG4pynZrzD}T5=RZthP5_mdNP=m3eR%LCd z8Gej-qZb-4q?z?Z8af<_G5l@LWCbvHB%@VM^P(X{dn#udPZjy8CR=><{keY$q0Trw z3xJE`dQ0cky8^Je{t$_KA6cZyCe8$!?f2bUO(M{E&A4*~_48 zuE}mArLiqy>N$9Jyc^ywCm7L5%X~XoUUQ-;SND~%^i-yKju%H&!a9;NCA^e z0K%IYyCAv|#qLD4A?{2}+jJN)O(kwio7Erp1+b7?t-*g`8FjYo+_MKF)+g5!ZY%?@ zzMFNF(Vj)K^exu#f8Us&5B3FUQUM4w9E`ea4=sto@VT#k&x8{T(_0w&(r)Bix{_37AY^r0w zFOG<@ne6ld&-G=rv$wDoWBhSe@`CSMlLln&nWVkR#q^s2DMzog^s zc=i?JmDr|gM+6SqL64CyJMyOJ&X#`C##B@e*gUz>Vw1Y_m9w~PLYD>VaI$0%6&8$A z(_YlH@_H%pxPzMuGM)1JaloE&zf@$MK&HSTyjUZf;Z9FVl5_9x7u?bA{l2S1k5-O3 zqJ$qx7t(fH7g5iLzNF}rhfo|Z$wC=7V~K60*_zH@#4cS2lo4BpZM^nBKh|7BpUOQD z^eX01s|WthTaQA-aR>?3IQ8CxJ%Z$QqIMhn`+}rI)?5qLl;D*-Xzd1i>%3-F#ZrPw z5z2OeiGGbdd*tqV=x;39M27+Hz$99|wU+1|KGYqEtdarSh*W=eBxoniY9XUg0x5rU zmkDeA>cfdU-4UEPJ!dzEV<~ZAxQ_ykkT_lrQ5OJCKNt_sdD>cKG_R}+(whOfL|#ZP zzg}Prb5ofSW!aIcK75d0bnfMlDLNJ3;LfdBDD1XNUOZfdQ0k5sWyv{Kn)a?J$)7RE zL-zt{(Upgdnf59y656&^4s-R?*Z(A0bON^0Z06Uu*%kjqboMJ zS$u`url8$a>I)tdQ3wfKr<6KV$E*uM9@XXx{fqsC;h=TtPTjdx=}r-whi`k8UhW=h zR=kZOA-Tt3O`N`SIRE7RZ3Qo;g&cVSle<|&=58`uNcPG02dPcY8Z=!CI z^daN|L3qg@i&Q}KxcMj)#WsAR?=-E5V&`&! z*-m1|W&6);FcjXa@fG9*ojEUoyVtm;m>b#hQ4*1B6UndE_>w4JB_jsPHMWX-#R13w zp&sfBOTDpRc)M{FC}252J~z?g7I?`u0}G(p+k|`@t@$nQVkG5G=1*6qY1A`(*397NaB$o1!Pr?1tBo{2IoqOKc==5xk8o^fb zp`&u)>VE0<*Hh|pc1cG>h3h+!JD8q0E2fw5x2b6825_T=bKhZeD}=kTUMcIO8hiV? zBkAn*q2@KD=S4+2Sic6}YxL1bhqd5eR@DkrW!%DYC~GD$5dAQetssjPid#@bXaoL%5NRSY}6pq@pB9Ub}IFQulk*1=>tVanzaFFrcv+P-5v(Z6RQL zP?jj^=z+@e{2HW|^uAu^L_{g3F!CHKUFp@Z1oP90_16?JA^-&0c<~(5b8YKd8Bi~@ zYK?qeO6_J8p?p&@g@TUg^m+VXgLGGN!J~4cknCiC496~?2+R%5jx3t)0-~Nq^;Qn5 zCJBW{ffm~k*Eb`!;{*#(q39?+2v>5z*z1LzFxXEFs0q6^^4>t4BKqJ~Q62HJz-#cc z`|zAnfMPu!2&VDjMXGw*Ul&uM+ewT2B%AYi7t>LKI>dl6k|=S_cmyEomcFa?y&!Y< zHgQqLf z^PLr?FH_^yt7aZ>Fx(Z8-;fb3&&+A$q+S13wms8+^HrLNmJu$P(r@ml8Z0m~HQEwD zx|0QId+8^F?~7pHJL=n3U~9YrPwKgcFd&c`SD#rQnrZ8>Airx6y#tMeHO!}M)6`@& zHs4wj(6Rx$91OVcbtx}!Cp3MEcdJZ|k=JR6T@7i-Q>?!F+c($I?=Zf#R3V7b-kSvm zR+~er;1QA$k?LWNtrY6wct#zUdZdae_5q+4p8YCt8n^;R?4%PAre4m9{VZauHwiWhj~8b zl^h?-xKw>z=Jlx=asZE3!OE@lzYjSqa3bbflLzhecL*-76}Yq68bsJ!#t0Lq^^1JX z+!0hJxl)e!w1h&&eV=18PUl~Y-?(e{Obm8tifVwOe4nt)h0(ruPXUzxd>PeR(@RXjy8ZYz7oqT(I_T_s2 zfv^z3n&i^ed{?r&WO-xtTO5E&A(|kk;XO@C$PmQx>*~kR96Es|4_)f~=@Q#l zKqk*^r;ayYdgaq{ns6PLD+&A*h<%ghgN4MdBT~G2lXeq zTSjU_v$!t9fQ@aQuo=Syz{6&Zt${W}19attjH`~kx2G?89Xpk%#9${ZgIRJE>^ij^ zvo%Q87jTnRI)iHpZ3GS`S9t^(O0&hJXGdb)2r3zFwuej{P~9_Uw;b0 zF>|S-ZT**8MoG<(X&`Q`1YF^hYb0tmfmr`c3Yh+BQRTz`m}#y00NbN+h4iP`v{rm? ziVT%LKrJB5R@bcRN-7~u@dvsWqT1@Cf__`%*e@8cOOikIZUQ=dETT=m6GZ+7HhKmRO_!v?(zx2?sz z>4zZ-MTJcsi`BYntp9*UuJ+C^Hda`^(9E~gN#^LeliinG#c|l-Ql$8Os#ckxdPA+! zQNlvA{}a&%cG?!w%rNd%{_AkrDN?1rF>C%R?!X)sGQNC9g&3izugKJVl=b4WAmm zPxaQ5rn`qM)cZ1gk;~>dz@0hR@}V+X?#{y1f%#(drl?i-APLTV1E*m=N^O5`BZBak zzZ`GGk~nz;fbjyPC;S>!2cVFC%{F_28~C|1w5y!KO~6S0tc)b7EPyx>&XRrnaX#xN zPt0H%!Ok4b3~;BKd|_`1n|GI0jkU^H-SUW3JeH_19F_>3n5BdQcapvgkH+tGU^O&9 z8M$A<#W3`&jPVv7n|r9V;x>t(IItHc8>9B>H0wdRdduJaIdscJ1FHS+NzGYG;r8oR z`U6k63gF4B0XYJ)pI$T^HuqIT>fEeEJ@y8#TNn8p4mRD080?Sz_zmSfluQP!$&^vO z2K3L$qxK=3-v#+ix-^n6D8-j(_J!SI5!Ge@9C%147y`x(=|EB&oT)rFLuUFVf^Lc5 z_WE>9r(E!{E{~FLMU$3CDsA7rYB)!}8#44s5_Z0M&v0_aQ|w=beD@@My&6X^Yp`6C zeVoVu1(2R^mguHSL~JzA2TpUFFRp&)*sGZ z-E=!ZL&WCI%E8Ir?+>toxF=oB^^NpThtHFrFdNf}&ItGo&sil61x~jZHmCW)9k<>K zdy>^$)^#_XP&OgrORaNFc|54*`jQk1@3svdbow>f*%1hp<#Hps!8-Kbt-`R8iBD_nP0TX=>V( z-~I8D2?PVpj@h8F^&>z3pAsuAo%z{(4Y1RQ`(h^m>zL7$B~}lnT^}-Wu*uHClD-R` zj<&r2{*rR&WCWVm|7*@Q;RMZRaA%noXiiUn>oFJ*<$k!GK4wT2XJy1~&GB}y1ao&f z4mF&8JB2q-tbTs?uFz_qMrA_(HqMBoJ3dlis>{E>7Ry}DJI>nDtQ7vy^%m#*ZT|qjC?O~*MM&27*?)JgHz%tW*h28{#oET1> zCl0Hu1~a9v!CT?^(9*&weJ)J>Av-`y0%r;Y-0Q1}=be+HM$)YTjmYy7bD*~xn;Svk z=Z85fJ+Z^}r~6$w^3-Kcjya=)=Kf$@@5r#pa%PhaL_m}o{iG-!7)4bApG4=r;51DR zleDZm0V9*Y5cQrz%r(GLHeII^o$=}Z-e9+~ScU03myNl$P^f87=iqsYFwXltzy>A^ z0NZ3N{fj_QC>4*ZK>8t!84Q5!w+^hKUmen=gUAOLzxx|KvYC0hcXSkb6?29JJ6zHT zI#L^%B~-Nz81%o$>Q;XsJdU0C0F%td!kUcY5k+%_$#mC`USEYIArmC_K#JFu?B-Yz zGtRhs;-YBq%0(swN^!EVH#Rtu zVQyWR6Eu#7hqD`p0x!SHe9Jn@AL3)4akO%i47N z5(OpskNO-h#_GC6up}PA|JRn{ugP;-^>yahEOz+yIu6RQ5`cP$ejIiRFK?^F=4<4= zT?+8kMZ+j-{>LKQVed`<|4;oNk(r^&@hjgtS5 zt+x(~vTNJEk?s(sVL%K*K|-1V1O)|Yq(MbQKp46k2_*)UFz5zpX^>Q6Kn9SI9_ePt zVTO9wcsKQ^HrKhm`A zRse!2UE%Me5i+Y&9QBBGJIMpjB#$Od883+j(!zCw6YX(&gBG59YX%M_#`k&v99)}p zP$sz(^Z&dtymkVA1;HO!OaT0{EhY19 z-_m|03xaU%b4y>fhtSA2rxlWLi@S_55w z)y_aY%j8uifZJ8PTr`>kbaoXl$BG#7a*O|t6#u&p@)O7!z1K0nL>8ZF|7XF~d15Iz z$Jy`7jvkBb<=x7mTolv=O6;)ka8Urrh5!2nKSMU0=JPw?sKwpZ<}jLE-XJYgJmAbH zbs_X5v`N^q`ueR2pVuJ?2c6&t0<1Vi;7hlvD6NLpD5CL#{k1zUy9-@z+m<=gQur+lXUQ{vu(Og|4$U{3Fq@izvJH6D|TFwFdPxK#y)sU)AZ z*$PhM;aJS7m`ekgOkD+E#Xm87|1P%|1QsPV&PD2`@HgTYU;hTNDc->xM>K0*@%|2E zMTWIp-gUllsi~a!h(sl!6IxCgm4Cmk3Nk{4M-BU+^PGjD^s~C_*o^P<;!%t%!ySRt zqnR-SvgcMalWDpEyEB5C-}dT5XdQSrRaYE3PW{wS5wn4hx?ta;2bVDnMO6wL8*jk928uoW7XB;b5t%K3 zbK>!Wx$5chKzXZSQPMClnw{)D$=L5Ff-NozLP(h1Dq>d50ee)#~*$aOJ1 zjJD?=yUYyLQOZX#pKD`*hPCT>-)`h17#cDP#=~oA9&gj+3lVkce54%dp85G6fK9Y~ zHD|oHm#>jqz5_gwKEuH(bFD=`cn;8EX{UBV6QIi1HG@Zr))k>-B8FqY7ctzh&h1h- z8$FfaTDOemuTt2JS29&|4&A%7EVTyGr<2xE99tr8qUn&%<<9U>8@y4g-vRE*VjCzU zI4L~_Lu_Vz<4q1+Y%n2&Fy5p4-0-v8nO9kv$ReND4R2ap5sB;(Vr zzPzG4n^HeD6RLPA>vsUy=@8gB5W1haLJRSsbD5tKE6uIb)V?CSSrd4*prBy9TMLV< z0bG4Od=v&;l9Une{QxGXLgn=M;lgtk0g%>%_i(hTD|FExMWP+X3n7cQj8w*#>4CkP zpH60hU)yMPxyeX%-l~+Kk0{7Lpj7(|^8gn>X14-nKe`QvTRYi`LLW=4Pfy6gQ5 zu;V6t*SPR5w6M3yc@vH_wgcZu5Ljp`!k{8Y0O4J%N$J0jD0{xHpZqZ4iwb9gYl~is zj^Eixx%&%#xV&H=%(`eT==@v;mS08k zCk>=jC2gpAiv)ID09WW+kBpn{jT`De-^3BwNF{aw48E6XWMgUQ^%Y!*J{Nu*1ICQG zF_PkTOAli?ESkks3~l-+{PhcrY|~)fMkrz6BCFqHUMM&x&n@Fq&bfWXtHSb*%ehsb zQT^wkoJXoZ9wz3ScfmT1gvsCh!2f{JRcRzq2^nb}d1$0mE%z2M1Q_&ZLfj{n)>LUc zelG4g0J*o^2ML=Jg>&kq(n&2qp;`zi{_PsFyCD1>d&n>dml)t8#h{sJhK$_x`e9Y| zAYrXc;q-_Ge1b_pGOKKlQT4H!`t~$MA_W!$e z@$dNp0sz2O5&N_MG!1t&;Gme&HcD5K|@DxgW`f&oW-;CFxX$v8iqdh{%s zJxUF!r)w(+`aTwPZRyucX_G=%(i;s01x$+M@_zty9;%gMq1|v|i1{eaEpiR{;Tn7I zqtoUCE|Hk#GZ~VS-!WBk;Voq%^k)E*%V&R>A_v&&T1vM`=9E$M^}?#9O(`$z05rE@ z@A(;yAZZ&v;s#+9!x{I;7MF|M&{KNmllhQunFA}>o0>DnpI@b{?^Y8WRN$iu6Uwx8 zOq$oFQnmX{i@#QS&UgD%)0n9a`{6+UaPWAAePU1{;+rgHzAfaA4{YN*lk4Rp!&0-% z$Vl=Ar$2=9foF1^xGp$k&&TOt%>W0m_^Tk1v!N0aaKzIoA#B+!{x|a1%;Oa2F4XZk zo=vt=5PQ1_an*PjH&$HzB#1e~8@Sls(SsrwJH@n4}Oj1<*Y286FbZ=8e|Sv|vl z6|TeQQsYMBL+fK@*)1QRwczhhzZoHf5NtKi(${5#I+(JvX*ao%0O?-uyJm~8HTpTv zjWx5MHo^I3hJXVD#DFS&s(8k%UZZ(>UvH63;*!%L1*Yu&ts9y@iN^Cs!U3`5yZ^c) z(dy*3u5LZz4mB<;odHaD_n!Xr&@b0gIlD3jC1sAgk^@5RcHv$b#+LNW;$T&XXc;cO zl0K3v)1SWYnWkS^j#tZXkfnIvJ={t&3x895FgZqM>o8>9-95Pfht5JzY|-qychs9N zfMC2i@7KN;KY9ory1QQf1J%VZMr-F{ZgWyeC4U4J% zOBeZHn##FD^?v3z6e%G5BZMB*(mlXJFt4-7#$P=78gOiszs0UoPrnbMVs5Cp0OTF$uJU_olMOb~ zd$Z6F*mWqP6nvC7ec^Z$+~7kHR(eXqG97Qee2%t8HU+=l3S& z5djuRxRtE>VM@vpDRw;u$*94>2~-|h+)>`QV$Dx~X851FvMfvHD7Z}WetUG*{^R9B z-(nN(UNFxl4JjdgOxZ|yMJwjz@TW5Nb)x?7E6k+~+w9~=^e@LaNCLpctI%$w2q4C- zLYtKfl$#B|JdUyU2lpT_bz2n2p`R3JH3hq-d&>t>nJJU0PinM$)674FRaRS`9tx31`)7GI4t2+*d41=xpIN zAVdtvjE?;AQM35$PN2wJTO-m)qR^q}DYJC!D>euK7D1$<(X)076^7$5cFkda@;6Gr zy+i#RZ?-gJuR#@fyUXTOPjGsC)-&NThy^V&{R}7PP@7M@h5@+&RyM!D$oeRyqxJEz z1+SF)Fu%zB?(kCI57e(Je$RH6VCK*zTPfc{#7 zydf7G)PWz|5yhxr8r-Hm?VqmW9IvPhz~nu`^ftK*p3bgDaHPuGJs!@f(o1?Za$pOu zv|OmUZ{go16GMIF6*ElsA#ist=t}?-`JV)i>2QslK4Vv>SO+lX!X2ePO!}fxow7dY zxafKJwL+E$d+pZ!{)5jyBCn2;VPKm+bou;IwUr-KG-3NBg^Kj%a`x5fOCBNUYhc!?GqcSB|tE%psI6C%SrVHTaw1p@j)zS^>LT zL+N@?|M)4h^O@GI#+7P)Xv_kcTYjl8H+}(shQZh)!1xrk?tl1ARbzRNdD&SoSH4fU zVik>LAq>pcO#;y^cv3l-wd(Evt@^{tv3~ zJr}qblYy^8N$nkY!GDeI_;I>O=DOsppS@zZ#z)(UN>0e-BfiiT*t9jbmV_}#LD6(2 z%7jmitF;8n6vzTfr~vRd=TGsQRB|l;?2=RZZL!Jtns@gFuSwv$?H5T=xOMspc=rj2 z$8sHZ!jI;*SBx*6q0(6hAv(uk@VER%YLD+&1sCi0aF*eM9PBh8?dY+CDU}AI5TUAa zjx=hHI)`{*E^DQIu{5N=NJQ=jjnMlp7twMobh%|`S0tFuX-oWY^&yZV{h8Wb6fn$B zso&eHFIZ|)y>y0GlK~hj#~b(_U8oDF*z&{4p-H!ZUV!GS0M~TMFU1 z3N@;4Q~gMyhQJUv!T!5~2r<-B(ob^d;7Us+5|LERr*+m2RC8}11;H(WKkADm0y8v8-D7GWj_O?r}P;cU|6v`s}Z?ZSvGM*K55H z{1=<^?;H3@Ajfe+{Z>Y`CZ!SdKNKJ%x!ZzD+jPa;!%=vZKK4V7n%?xC7bi z5jGH=*l1h7E36Acl@L^GzCzoLgx$*;l~Gc=88@@!zl>gLjXEK{J;R|i!JgCDF5#ys zxP1Ex>R?hPVEq~_bdM5M!aDDL#p#Ua&f{ThZF-I17^%NE9rv8b4btbb6T_Bdw+X^G z%jv4Vf||xrlOpAuMf^LvjGe!kBzlQ@hM<*r?87fYBHDBx+Akj(TUFD1bFy`Q$mtF% zzO#2=HVg(dL{)GRK=B2hOaYz_W{Zj&$E9-^SyNk6lP6}=U%oM0{*-9BU3GTnFle-9 z=|2wZe=ir3MCd1L6B*JaRFT8@7MF&GIf_?a{X0kvbRO2X8~pxR&TQ>nqbsM~+;~d( zA-j^&vGN_gy6=*n!q7a^Wr$zA|1}bDw1=#=W4}Va{i!9S&xBuMH#xW%1>!|PvTraR zV-hJ7!5{+PyXx6|7mw%RrVL_nu21FOtP>TMGlzL1@m@>KCTVFi2doJd#Hf}d(gL3H8P~HP|+o7CHyg-Gg*`XB{SglnTZEEWnLV+%Lw$xnK0$wEv>Oh^n-^|2vujM8} z`sk>s7hd|#AJUt{o1d5p3k$P}JR^=_yYn`j4$@CV%eOuA?U*e4=n?1tTS32`J^$>g z{H*;NkeWTA-GKY4fU6N&1teITYQr<%d%K9MsN0Re1@msA%T%VWd|?~i4?M>NCdix8 zvWdMSbg-yaekx0|a_57nHKK1_0K^ixS5HLJ#GR}45LJ;9YLed9tsh!knS{0E63G%- z6_a6v6>?>nxdx}z;djQ^JC60&tYlAJ9GB%!Z{N76i<&oUeZ3et_a7{wRI=o z-!SUeI+_cq7JUXRJ+?@9H6TGMvuuHeyG4{^fDY?`h586o*fhk@=O>`F_HG16j?O9W zpuWlWSKiHogGoYmNymj+qH-;D^xcya@$xp!g@>3Pn0y>5GY!_(YyCHB> z`M1fXq1bGs=NG0=|BNcuazSJ|Uv9t8r1~>ZR^dkjwkId<91g|RkIZgc2SXU#(uQ(0 z!L`MGuf}bCifFn4Jj$U0p80}Ud-=7YQrUZ?mKpw&bb}u<=WS0SdoD4t*ba;qX4^>9 z(2Z_SUu?Bji~8#O3(6+_vUupet_7z2BK(8-DC0qDF6V7N7G58(4HBuJ?q>beugM}Afz8C`-J0wl#7NoD zujW_BfDRwZ_xf5uk2sQ5<3s)Of;mVP=3YtfNXPVrN{)64|5o$>>j9C+WE?sngdb1; zb)GmtNt;7O3f({A0~Tr?i|b&=PqK0pEIpv+BdB+-tD!l z-?b&}-Aq=``?poXC3ji3@3c6uqqOt%6WaTJDRF(#?JNli_Uqt98CU0(XL? z94hYFGa9P3Tgra*{@pQwuAqCx&++->)usC5DN^0_3^~|V)5E~8+6`5!1y9X|WgtFb zn84KqcLBX34%lqp7m^WISgSi)jFiMq|7#A7V2y6#TLb<@Po3j-Xa(#fU~SvJC<9KG zNOtpd-extyUECMP6lz7oqLqc^SETI&185L>->MJ>sIA(=+& z$1ZW-YKZEn{j}IzP<~QF?81Ug)47&d;A;bzh%J1r8qN3-NHPR~QjAXN;>S zfY|MK&?z)AtHfG8Gs1u5O&Uzn8*p0j?I3Wb1SDaRN#fh3ghw<8+WHh3+) zh5J+B%0Oln2vS&i_Z>8!{_Qw@zR;cgw!5!jtgU*TJfwcE5qsO9#FjbV?8k@la-%mx z9N2v*Iw)SyP{=&N=NX~#Y(W4c({|hh$?oM0oV%QHKW_}}mEmpkfUGa@^vzcr^^PMC zN4$oN6L^PadS=3UzZleHi18$^90k8mkoVQ>FPZ&jr8QAKnC{_-&X%|}`BhFh*H7~X z?Y;8oL)*c}HzpZGT3r5^IQpJe{=7LS!Z%Q@Oea%y%u-^}6#SM+sB_gL`~cEJM3USN z)BdrWSRZ31?eabHH_Z0IYy(K)lTqfKBtznNzZ43vvt+6+LC$bNuYu6-ScJrG@Cxe$8MM}-02%RR~xmw@p5J+x- z0`KWs!=25=)?lI(A`A83p9morj|f8P{c-z$4nDjDcFF1{no;uxw>Q7$pAZ@skActk zedrtOk;o%D3O|CUv!JWOb*TU}`tVtHn6Lt$SD}&TXtYzP0|6-+U}U%LLUc|*P@%}$ z2O`j=(nRGy`kZufdb+wfSu5jo#_P`*Yu|mO3g@~9W2nxcUBI=RpQ(esmZh8RFi?`s z8fuwq#~zrt571FxM@gy5zNrV7$p09A=?gdXYbi>m7>j_>wC`hiV_Ct|UQN)5rTlqN zae;8QZ9E2cwu8BjvJlPS=r9>W0#E+}4i&1~GGdaW?3%YQa?Vr$4SoSh)OYy9EOZDB$E zw@gRUmCHG()2CBHGsN8~{8Y(?WhSBhugw-*a*#@_6Gjq&)mvY08*rn|&8NiSH!jPe zudLk!IX;~Ta{!HHZF!J|mpJFNwa1Xz0>dr-RPf`-Ni+qJ8gFsCdlIo+;*MJ;GJbzl z&(7TT(a+zUH7^2nj(+dV8!%rTe0A)9^>Q%WH;IIbsobb5r&22&8lyv&&Tu{I9%oL6 z5`rN?Ib}YEG^e6XQ4O>M3PCFjA9?ag62?UpU~m`;>dRl1*1dJ9B37L&Inz3A&E>T2 z^kMLnlgPd6|4JxhX6K?y2Zc|2oiu6WQ=Z;J1zCGLKSYm46_O4 zQ4UA5D;mWK6afcVf`EZQnhIN}wUqEhd$8yHkKr6fs)%azuE{Y7cnSvMZBwiYf$|^$ z@o>Bz&4W%glRsKo^`~+~JG;IBSYz&cRL|vHCVfZkRek{B;{K{wIqD4erK~6GA&m^D zTk!f7=76@7Fe#H}t+9Zc!}+nFd$OSRNyTo@VdP`75T8UuGCz`#OJ{$v_wj-sF0x#q zZk>EOHg+a3y;aqOBd1vj1Zc1JRMdz`%hrint0&Jl^Q3AW#fy;=&W<8tOYcuDNyKi- zDq(k*mZ4Rzh92@qJ;Z*sn&v8{V(K?*x6T9V;fO}neTJNGsNl;)%FYZ&(CLT)zzCmD zxWA^S6zin%$=5_Fu%%nRZxPY5z1F-anvrhGp{x8gW~ITXEQz%yv!!K4BKnZ|40R`L zHn61Fmzn>K4_}AOX^r!=qV&vTy~)lLLbK#auQ7@1qWY5q2gQtC_Y>g(=bAI; zpYJAaFXGcJH|S$17fMzTMtD4!5EbEY>&dSSsncN!n_h}EDjWT=oKwS) zR~1poSSu2tJiJ|^d6U)el(jauCipaydIc(L%~_*r-2GF*&A)T@qE0Pe*YPW~-?y;VheLiad&Q=1emslqx+ zGV9d_qD6F1zYQjt7zW1Crt=~OnsL(+5+SAX^Db3kNa{tYB|_n|?<*6iQ~71lg~P{z zunkGz1U4&$WJV*SChPVY11;9h(8pOPD~Ypi%al;wVP&lIB4+87KSdjwT_6!KdRl_6 z&)UdvnS}>@2^93Z&qs9hDjQ7Kk5hZ`*b>j^XDwb-bc-wS37eBrJ9ep=5s6s7V~!nRYmG1y!Gq5B&pF1cNcU6nnrnTX1PXH#W3L)+n%rJAiA_2YQ=L!sVugp_P{# zwb09L$9lNB7qk3AU6_~&Qe0t8W^-Xw^D9}8u-?bV=?i=Gi$~Oh*AauB2iq|e#v>B6 z{DI5~Pp98)cD=;COTczo*I^27^uAOkI%+!evCcc!F1ZZ&bSVYi--@>R0dxw z^OYEv-se`+Xk9&SCK)V?VUx_1KzMF-ul7FsiMCZQwEH>nLKryApH(yH&kL z4!KVpFh_m@#7a6qLL>cyiHV~t?hxpx^09l%zW|@O(7e&(q*Fro*;CNM^XYTG;0<5# zrVhF+_&B=uUJwhD#!H$(cqKl@Wo_h3Pg`4Xt-R+JM}AJbq5%lM!qTu*h3?&`_+NGF z3j!{2Cp~{7Z^d?^e)7c^E~wYuh(|jYQt6H6A^p~^Ks1{CN68-XuEb2jamHl&=NZVm ze%YN9W)`b-VTyeIzW?ATubITlcEagUDz2*XTL{3i%k?4&*@_R1$2G@n7BdO0LvIN9 zH*<{G$ZeoTOcLh9EjPt**ixjpxV?xAwArnn^ru^Z5py9X#-kIWP3| zpE)T-dU+{>KjWxIHbN(stz|>p=}?`oq@0q#WP4@eOux?n^+hp{SAeU~y{2sP5v@o6 z&9!(*F2>$0+Sl?!w8xdS@Gs4~3caU7A?$QVghu*;T3q{+5adE%6+Bw~I{Zd1+ zF~=V4iep!{n+#FBG+K*q4eI6G*TnVf?rEKzqrXPwKZjJWPMY5(?61Xa4P!ocI zDpwZu^0j`gg!zRs9~`2-Los^uw94eZ?} z9&4)jAw7uws^@xrDTfx(B#W_;4sVFd2XMl<-GFSH)z{;P8DGpu!K64pf#3fzl-Dd< zXS8(8Y0>w_8XK42Y1r=GZ6Od_D-t&IW=)JZeuDHmzVg1#S}CUf=%ewxG)vlovd&z#3ELEn%D`ypD!pJhynGUVex2{DCuYH3aP6*y)tqxe?b?u~XGysB!YRLo zSzYjPw1*RQ26Y=5eQtrT3O3fG_*W#zQz!r$;S>KTsMQQv0?-x;V#v2~Q$>@CLa>1> zUI-&!#7ULMKFWndY^_4X=TJbXV>|m0`+CU6Z;KB$URYL&tiwc3q<`K$&EGfX@0k7a z*+po$U{OQUolVfcxot5b(U%7(9nEGkG34gy&d@CCf^@O(j(fD<3ZLB(EXwDgvP&OK z%1xyj;{|m$I*NF%Cqri;YfGG zs-_>OR7)L7-VxBj^sl>~sSVHBlMO1WtQevjqypKhw-Aew?T?R}Zmqo46}AhkW6D4t zr8sNOf57uVX~?qsm8R@R?I&V;O+7gaQnYl^#TFzGtqDI&>#4JvCsA+A!dqyzRCQu~ zP061pctS)!ma$7Q?cBeNc$F{@iJvQoLb8sDCuDE0xm%6BF><=xIwq^R=cl-w&y079DQ0^O&Cf-6vZ+bmJVi+qiMtN4hsYy~Kg4ImJrSr4&HJ=_DP?nQ%d_H-mbaWJ^IOyrt)CWqtUmbxUM` zs&v||VI|~`$=KcHbP01GL=tbU%Lz`~z4wzFXrHXWmOu0=oS!H^`Xq6!t0AV)dO4s% zwLTz$PfrKvb7317gCYK--?u}M2I?r@Ph26Kt7*5lL)fsf58}n1cV{r-jL?VVy3e0I zdoeYyj7q*`n)EPP=;wJ?$nqnN@@UBnp7wa5uF1*IdmHmVncV9=HrZei-t11NZKl^h zirFk-#i9FsxNHCWs3PTRGLGew+@>e08|)$y%X+R&Ivi0K_gVO5&Tdd-r4k}k==mMQ zPV2D40I`q_Yqp#ds?B*+KtX6dOOAf-DWyA)J~*Gc_~^Rp+U`sDvgA@1Q%U`l{N+Xe z;dY>W@&SiL7zW-@M*&U;e^$~9S-9xWuxgq+gk+MKxFNn!ZB+N&T#gpKTBZ4VKM|^{ z)kxpE;@(zgga~t@GN*rMs63*p-?(I5EQbM{8mTG}G&gzA>q?7`!Q}!qvF-wp=jbBM z<+J0|PDhRC_%K1LLb!I69Y8m;~O~z%_ zhOI#EcQ(iFqfId`7f=X(RKDw+zFaady3as|?DX&C4w|shxb&qam`u1D8F$LZF4t3l zB+5Q6=Fsc(-zwT?r3)&EQsU|+Pk?{^GPdl`U`8szp^~1>RkvI+i@Zp#z)obVQ?B;F zE?2Iqa58|>>qAv#jR<>ipy=&)kFllMw(~YSITfAj@n5-Yow#Qk-B$_)XDepldRvOc z%0ax(AZ5>lQZ9>qI$c|xOc{Ey`7TC0W9$jjX5FC5LRZp=?2O>whVwd`gjwt%&l+#2 zFk4W96w7V;;B!rsq}}vAe5b%#KtKC(W3^t6Qc(1#`VfMn zJgaXTQ7~L@k8zeBdS5X1f#_i%SZPYM`>dhme4*TiWYlQT(xF&n`K?VRF5;9~6MU{( zy%XM|&Lq$x`#fDH=q;bM9~WO20o7p`bpBJ6s9D5Fu=B|b3x^_>ZPBMN;Jy)DwEPCn zB*p{nn@#PnM`ln?Q#!~u>x8};2(BKU6al1b+Yu7zZ*WmHP4~c~;@bs5F4T${Ed;Kj z8Pr6SpmLUMt>Np!h!FE282-eFW^fU`BnsW->j)BxrAU}(xrbxnppwc%8-p5uWVVi) zsM)ScMD=FG?7T~?QEcp1*DU3Mc5FbAf2SuuA}gynyP0tiO3aVoF&{ya&+h3QH}=KP zH!0-OOkpyh{bUDX?Gh|2irC<L%BY1BjL|ax`W?c-eC^Gxa(xC=OZr7HnEOGEmR06 zfDrCDP$~Ih(MW)Ui@wS}dxZ8aayRgXyZCw7)%#F8)$d~3Y(kKaN}^gM5kWX(f|K;# z#2Rf?aL2q=8{FdV#ttq@q);MrbL&}fSJlSkW9}zaavirFkPuxOJ=_{D_7`3}V;O5q zFHCZQxSSmA{M~%PT%u=iJkfRa%W*W#3QSimllKF_J+w?+tw|I#T;e;L`w{gufsT^$ zZRsOG2p6*`6Q16=DebzXA)uW>kg5=9aRV(v_WILfGAdH49qMq3^c@ea%)4QAu>mu_ zk*9!%=(OdpQ5P-wnj4)gWX@*JyYs(xThP#!0r@l9AjrKCAe1@yPYSEnM1zVQ>_5h| zLWare7xd6qDnpx9E}1$K{Q@%aRFPrigQvXHm3e|MOySvK45q`DrRB4R~)=jBXn zdp4QN->i=2@oR(%xZ*dnBNBekrj)7Wpvm`YwLtEm`>AE-t9xk!HQrXR%A%(wQ+|0?J?52O{FKu4 zj^!oW#km|0=vHINPfIs_2SNq4+}D$lmX81wESGv!OdH<+&361GvFiC2rQJwh1SavC zE7R_*M_g{xcCocwT#!F#@hghm_?a8^bgT!~dm%01(7wOJGWEryG}ZZVt(*`NO6S>f zB$)n2wi+fKsb$WC@KL}se#pyB9)b<&cIurdZK%4DPN<8lUKLSccD_X(!ZR6C>WsV9 z#F=y68A3Tz1jHa=4Ibrg(3P#Xt=j(6F<$^q(KUX6GRB|gO}u>O*am&EIC zRSVyRI>YqKA_e*PyUtJckY;&8-CF6AFbhgLy0LpGKn#@iaTpGHkRES|fkc48TBYHJYc)@RO(!Q z;?YOZYoTv!s4nxV{OUqJ!^Spr9fs+Kxg=(-`6a(Q4(V~)w(!x|%NNed3X9r-4hRqT zeBj{)Nb%QKVpHcg%TgL1Br!dn@(7hllL-!-dqPYHeR6R+E%kT>x74ypFh&w(BRrP) zS-|okuw37X{?%Q;PeiPATZ{X0JQ-x~q8|bqEghP&b|?2il%#zrkPHi?#(T;h<6+t@Sr@k3C193zxH?@386T<1Pns#ow*9dx8HZtGs390^ z`mms@{+luc3U-oLw0O8Z!M7qlyqR%97$@FGAB(aoOL(2zhyVthW*<3@w{t%pL}Y-O5Ss zT3)ZKbf6yB7rGBn3+xFkw3v~97=A#ITfnU#cs;9w*wJL&DzsknneXw5GUYziAC5!D z`Prn2P=1n!(`ygq>^kq>U3VI1XKPjzcm-==M@ z9}XbG?7cY;qjuMAwubT&C%w{xeU;q~gu`Z04cu4w?C4t)u)4sxjB?YuS?OZgs?FS72>^!_t5|1sMwSxQY)ZQ)r;fwo6fRS9ph`ZCf5EJ^ za+sA&R^?mwCJh2HlRGgPnLVYc(ts-QS@Pv0BLKjYde{tRmHWUy<;r?x2s za~ubNlb_WQL8sU3hb;huOg!L4tuWM;1G^7DOGe18a)ks=Nsc+e@#@|8}IW9 z1OlpHla_{8)FQ|TY&hjvgGlc(f*vz$=EVCMG-gddVr`@-qocxyAMr_qvwrlZm3Fg- zndwgn;=R9yz&E7VWj;5!$r^mES&q0>B2#f;x2iJia(%Ue#gv@0$m9wv5!;YSw*C^{(yWE); zAvQ}f>lyFaoOWJX)4UgzyzoZ7I`-%9Air^dw-^Gc9P?LMiIvp+Zrj@66WmAZxwI0F zGbMX(v#u781jy}d0{PD!FjRZu^Ca%cZq-K+O>h24Nst_JmpGuE{3IxdKtMN#oP?D0 zesYs3cQ4Rjw2PhrQJ`7)OJ9`%-XAnq79AWMyyr}tbcn`dN%-qFHa81RYaNHP?opj7 zT<^H0mq(4o;au2_(&T+RpEZN|^AxS_o_>-3n@%_c8R&YGg}e1LK_pI9^9%@+UA>>( z1d@QyHcGDDxi5?-Y8=>GXm+6>Cqk`bqTc==h9r=o5zpuXDxo-#zvCHWdBT%i`TIOK z9KS8d;l5zfhDGd0AAgec;oqEDfwfk5%YLdHO{n+4(Yo)iYUHXX{E<8CzGXR9(rkPt zv_uT`)HwSRcygp^cJJ2>*lnp%#g$EkJ8huiAAP*$5388gDPc$2$m8ybrO1be=6U$*F!s$i8Db)Lfm~-;!JbcPMx0kR|f|% zbVlxnX$USuN8e(`=QRxo}oEhkyqG-$LeqH*yM5^LHnY3B>GJZ}!@44}=Iqi8vobdd9loj72-4>)si zpxGnvxQHXM?AZg*+}ZPnJ~=U)fMDaSGaj>pec?Kg)$s81Z~(>p1LX+X+*0#Km;Kw< zCslmt$RT?4ST%zXHEVh{wj$#j0HCMvl(_k3g(YxWN`jgI?r$skmvdHfDb4Hg*Np1-^Yt3>xC`> z`${eYz5xLaWV=yj;x@Tf?kP~ScUM29Vv~Bxl^@;lS;E8}@5j_IKq>d}%COkV08{1t zJNBbFz*Jdr6>K*$#zsckfL|(w@qDI!vbT)giHF{x27gHY&^ps zs7*fy6V@n#LMHHJNA;&f^CcXAfChgxG8r8G_~=u>g13~j=8NH!f19WIG2teQn9tQj zJ{`HogtIfvH80qEKE9dn8ccB}TD2}HTiSUJhI{`wZ~)r5`8EF6c)Tr`QiFfIqrJU* za438kez1RsH@KOabW*{<90Uu5dkTRf& z(~QUlVjF01?hD-vj&y@q#_JjxH0%<1O)SmC{n^3TmKFsq&9@Clr@)T zLwrI(azD!h;LcdK*LNWpLxQuQ>mdrWHlqGDW`TOC{DZUy2;6Z0>(<2sga5LuL(pI} z4Ls?=g_M5eZp_Tgv6ZUeYT&GqP$;~6a1M6|SCC~Ks9>`q=pbvOPv89n!s)n}7@A&a zLZ*DqqLTD?Z7^t+zC%Y!JwSR$^Cqumu*_0H2=*(FCWb{MMDJ+0P%mQfS1=Ko7biId z#UC8KpjBt|pToh@2H{s@8A?Qu9l9;UaO8vc>d;^OHynWeH4^U&zDfg@IBy8oU{c&% z+&C8(7vA9$`!3=nJZKF53}pYEquPinD=VJ?!v4~IUe#DUVfB-g^A%%LQ&(AV_-29f z)ye+^V(sDKkpjkCM>`zO=PQG}kAfjAEZv*Dm2SWs02*cTcyA09pN);p3f3hgJPufE6P5f&+mbHkIz% z#h(TZzB|s*G8iHGC3iddS5{`KfER@SkpBCsoUpsrv3{yoWr&*udU)nQxu*FmU(04Z zhWr3|`KVxfe!k-h*CIYd%G=l1)f<=wq^oHV2ElL#3D`{EvEHO4)6ohtmQ&WtiNL?h zr;5rLem1vBsIrw!qb8`bU^VGH-#G|tIql2{{Q2pQRYlA5o{OQUA1_`(TM459#akV0 z6VK4+m|I5YW0rw~zzD)@ex)}8TppKzpl&Gl(I@dYkIO7hEu74mf+4^%0#a=Lz9PL# zN9Gfl41In*5!+umxiNw@KMKD3Pdh$L7YZ%4SgtX*8fLiomw}DXHX-4$eS#o_$OWFI z^ry;p#bZDrWFuXs`Gl%|`kSw3(gv6(cUzZ1e$qX7y$imhawpY~0%&%LR|UPzQ}UwB{wC zfP+8&@9Ufe(u~vD^V9U$SOk);GytZZuev-#>ON7u_N3fG&Fuerqf~zW+$>SBCs>+t|cpw}$=@*hOM44B-@AR=0oY(+5L*figA0b*b+` zp>FP6&)e!OaK&{=x@pX3jY#l&)xEoeC%w_4WbMGRk&{F$Ka=wU-gx#~f5r5#G>lO; zeIMR5_#tGkO#9K*7SlX%RVITH2DFcqXtel-|(O0zn+Ce+1BEaERic z?A@W(OC-?mhhS!EJ6Yq9LS>=@>A zawHOZZhwofYx0)V`GC;C!}ZXB>{LkLN&NB4rh>@~t(8DOd_~|&02@O!QY=f&NF80u z(@aH-Q6C(uL;lz2#B_9zirGrk2B852pMxc{&5m@|y`N&Q^yefRSzwuIcF#ltmZ+IE zKg$?#rNDn(69J`iP353me3+aMv|ocUVi>pM7Ux4QaPxZembv5XtKN(pwxGn5%w)AO zX;N4}gWkdTo1P)$bhG#LR?mU!bEHxt@XBL<`Fo>+C-o;Vj%yv0W1cWILFUrjcR$p1 zz|7KnK*^yOEKgzb_T~RMg84vNE0}n9z3;hOS!UjtbnnXR8{e;;DS#rtT;({PSGCS> z<9Ef)cKeZ{AG?eP@srI!l4W)VB;1GWtgH|4`dxRs296V|cz7_G#smukL)-hED`WCC z_hh&=W}+I7nBUKCfiw6=S>Z!JhNJZB=)I+%yoQZj1;0+G{wd}$C;Az~eD`OS`IZ9G@fAKgYK?znJurjKdPe{`XK|4#%& z7t=3qJhV=Ak}qk=-?g8~A?>0KEVKooR;ra>Jy3F3(08JH1m!wvj{9!A>UIAA`t5FPc_sY zk^cmHYei(&Qf*xA2X!zqleS~k4FucfP4$W=7x<%YP{s*eaHl_|2btxM;KP)Del44u zo3;ZPN;ii`2z!8%!@;7iZC1Icwd;UXI#&LocEk@JmBlNZaF858<=L%dCQN^*cJ1=T zi|u1q4qp|RR12iDlkAqi9L&0js|dOT7W8Vt+slHT#}XNG-n*}vDY++w%^SX-mVXrQ zEHtYZ4fJr*G@JL52iH`aKO9UxJ zYa?tvnxi_Sp0}ZwD16*zvub{iIKb?0(U{koKoU^G=Kk{M(80~7c+q9e1?2|jz1O@; z@$=3j@7(npUvO@Hp*;DGGF^DNuCny=*2{_S#vC+oeTkA=lP)dy4?a7kCwnU7gK3fr zXO7?J$D@}#pr0I7p&6N{5w4snXNY_DUS^Sgf>9E3LjA`Jo$3ufixMLx4xLs{;!#Q) zdJW8{A8wjd%{9#ZcsNj)eIez=jfGcNN4_wQNqUw}xxK_Vb9o|1Lr66LhwKV6r3|nkLAxm5Wx!`s=}zT@Bk@NDwgh##R`(3zzslg%@#CFPwwbyUKY@gEVHlXmZybkB?=hKA!(tm zUX%n>F9U&Z!B2RO<`eJ+_e9z7ftn)=EFbi;uHZLKpG$w20usVBDC4owZTkyt{Qa)z z)@BCKTAmpD7=j!XJi{d9IsIp+nTmvJs+g-%8&EiYa)#!5cEXwVV{%tI$!k704G(Xv#(*pK&_I5p8JgiyEVr6an^h?K>kCbtA z%Q7nGFw5G{T_l1`rE>u+RIC2`B+xa#*rV0XJNN$nxF-0rV6=5uvLbA%*?pZ!mGJoJ zs641^soZmWW~46$&N2CWfoYCjlv5W{DSG{SI2LrG>mfs4-0xVUh{NxmfmWIs9qXHb zg3u%JV!bx$LDJin)m(eZfhq&aZoIn}{kbtTylWz=`(fhuESv7D-2JlZsR6#LLdK&w zlv;AAKb70OV;QbBUB4~AhICt-} zjSR(_*?QLqWK@_ybSU{r;OV+$mGk_4&1xd7MU$7ac@al7x2Gp~wO&F-Qi4Y1+#s7K zO>e#6Nq`jOIqy;!@@X(3$kXwy!$xrI=N9}8k z;6f_D$o0cRPNPaKF4-8SeiKAIM{LcebfvjEO87(l2j2PkXQcd&1CSQEEXXc0BJKb1 z_10lgMqj%y5>iqkAsqrDAcA!FfCxxPNhye=NJoMWHluCeK;8?t=lXR*~@u7U1emvAUajCF5)wuN7T__JyGZGf$nRZ z;i?3TvEx4)X#PVX^HEcr83E9&;par)AV+XL<$7T>!e0Tx_BULZc;1x>b7=b2f@vw9 znmNM~9eWmN$GX&PP`ujcrq7O!%cdjuDJg$Q0k>C5IHNe>5Wn=ZB_(pCN+uq1b2wKM zXbU!hR(sua#1Bw+O?fy`SA8G!8c~|1)jUqA3~*VCrWQGcf3-0K+E9)s0Z}Ak1FAHz zWzf5)2@D)gwsmZljBki{BMnY(5#!k9E|UsHmU$fmz$AQ6;1`y{74_!|d2B6bt zc%@AfM;bs9;vKuWuPKR4b>B>WY8=7wT*Ts) zYGgBWxN@R3DK_)Q^Mog>oyNVy-)+fIiJLwQl)Oz{qeLNiperh8K$kp4r>8bxDy}Ol zd;ZroD@+DB)`pBg!l=uCxotBJGhUZIEKK;xDh%eYloDTFgo(ieP8?3-h9v)zl80P) zXNFRQo>>>K@P~v)i;a!rFzDw!JR=^62sP?IgD84r70Cd$w}afm2ilUyLGmJ;33sx3 zn%76VyTfh^0s59}=J7v@Z09|6dZy{g=D=;AZ-viiVQxRU4zAij8f=O*-%Z3o?Mj0M z0U773sO@kHE>+*$r@4v?ri3m6gh=PmC60bdzEIFSF(9j$2dt*t7Q< z|MNV%!gf>4KE74rn4NWI80Vr})@e-Pabz9M(@T6Rd7<{>X{BA_Ea%|dW3vd6bA~FcXV!R>Lon983)lA^zZ7yGK15# zl!xE6i%<&u2q3OA`+iJ(@%Z8f1y*u$a=IEd_4P$&*C(W4FVQ)+xjuXi?$!7^ zVl4hx<@gj&+l;Hbz~s6N!g-{Ld9iXH15omfQejV_(74zN|5gjSsq3@RiD8LQI3y7E~;#1#MnH#Khb* z^=QI*TDjY{`d}fSSEeA-ch9*_j`k>!51PJ&mI<$WRXiCL&hDEl#NKq@Fieph?H=u_ zt7b`leKR2CEjM<)Gn5G59LvYvovMn{<}%9thJc*8f`&Ncs@?Is)xW4%x9hbZ>k!5ebSqA;~7DM~KocOx~?+QBMwLu-S zS+sYz+HGE-VJ4qdpCXoqAt2*MpSGwwJy(7}v_vD@fAsIyjnTrAj`OfLGRKxFX~OM! z1fA)K-laOwwn-x7jOt!AK>7z3XW^UrowVQ{7CxsHeTR;Z)L>Em*0?S_TZOg`7kfsi zakv2^GMc;c8$LEs{d_t{fpS6xiFGGuYEJA+%FRC2;hzW6nq`-~pN~ByzF1o;+;Cc8 z?&bOYTsqoVeZ_Q=TI!h!I5U>gm^W7>7yD%kN_VKKsUvs1Pc}%_`+|k!POg9Om^xh^ zt7L;O`XyObqs*L#7(WKk+T;P59Zl$bx-2&Ir-H*mIO;tPe;bA_`P`okZB4~kF%X|3 z9qD#Fe1iLYb7b&&`NwwFC&oqSxo4%e)@q+K=`86|U!x!fT;WpggvbIh*@idVxb81$ z#p3P~(9ql_mb&;h*-f@25f%$)3oE#o-!5rBpghqyP9ViJ1zw_rD@;L((ptO%6r)?r zj{t%@MhaZYfSgQnz1D6h3paNmAB<@DkQug@h5tVL&Kt1SE4bj`e=GguiH%L-$hT*R z|1(cXVL}n4bd<7ZyGcUEk`Bw>M@mn-FV$6Z-ap3|*>_Yrt||xs?~!82`3)uBd3~Q6 zCa&E?os}qo5^y-r4rG}Pb4>%Ea_uDYFSzBtu{;Oe_8B%2-6sh>_Us>hqz6r4sc?#`FX zJb+Eo0*2vi6mqVsKxbFDT+t+M1Ez2q+d3f3HF`9##r6mgJjNbe#OMF}VsSjPP$`nH znHbK1kq*lB1J#p(#7!B6sA%-tqicGLAwTDly!X~tlO4Y9_o$RxS-BZf57-i}!6zg3 zEd~u`IrwYO-t+!y0;P@3E^iXV!u_tOU;(BDU@MRTD(2P}fQmcSBlS%w(L?P=l(0q!H31iA}&Q@ird<>xw7j;EDSr7#R=nY9jaZgsJ8}8(S)5hAy@rvuLkP( z*^k=o9$Zb%qdqu*$BGFs8>~O*-1zgd125P-`^*le1AcI%fAGc|F34ILG(wXpNK(bz zTG%B~egWw8yeKlj$?WI(LwgXahykpiVvIR%U^re`vu@W2ei$x^pG(#-2yR)CY=E9_ zkzHTS->N{A2 zQqIhxs;f&mE_-smG3XETm5Ud4WJQfjXM3}M;V+X#Vy6KM2EHy8@Th@K66)!v2rZ`- zbB&q?jF`XZbYJOip8`idV4kHwNJzM{v-1+{i&h--@zGGpN$ZpFQn2G&@w@`dfHg;x zMJaKJxiltp3-bohr&|+QWP2W#A%WSz%I>ZT@NLQjVx5CJUQpP%&F*UX!nRK<=b_3Z z7x9^N)#HfN}tjN&-LF!FW-wcdnM_agJUMnsT^lm>Brm6q*jf$^=;dVof ze;TVfhQznH_jtN^bFpImhw23OGhK?=>{!B6(51g)kf5=l<%g4@-WolyBjk?^48%Iu zD>1o4kHLP|mxzXzwhImq{y5*z3tv9n#`o-W`LejQ)Zz@B?8YM^?4Jp=-86Vz>7D_z zsgkefeh-gjRs8O~}fd%NG{X z1!m-9o)Eu)D9Ak6Xp|Me_g{hreHq9^H{hj;U5=YWEP$Z*LAy}D-D`JeN2mo%^~~*& zP^*-l5FF$Quynt@7TiztVUvblpXwN4qPQc*%C4#EpLT8L85vSW5FV%IeG^sn}mx?^u}>O z_90%6?%@l}e+diA0PHDt?_YNhkoWKdG6CRyUhS}o=Up^Z3rf%L=S&9#|9a9dC@1B@ zEV%`uWWH4Lf_aFt0DaEtw76wOFj3+3J_JNcW!k31S-?Y0rkr^L#5`Lq`ZsZ=)+yQ( zN9n{oVmWQ6hF$s@dbf2`G47O(%yfT`ukG-ccOS|19;%w$Gx)H(@gha~b2Yca=5+af z%jq>lEtdlZUA&{b*}=pi$I<&(u{ISongbC;9YSbpd&{CFh17}kCxw(1WtDtSV>k&4L64y@~1B@x8M%Ws!(`mgw znAmfPgRkbCXb+}a)pm`qM!q?(T!y#Re{Uza16H1b}3jd~Gt;7%g^od9i!F!3d8 zt{Jv3ebJ1X&aQ;g_W70OO87kgm6xNeUTdHWre5k`XzGtzkUNN0IMFj1>_fecDXJAbtuC-xH?9QDHL$Pz+&B zkdb;oBw25VS6uB@&i`g;A7)PVJi>+4FyD%232DqRbkps6U!PK_Bnd?W7mgN^y$y^> z7{QO|X(O_&iM(pv(s!H}gG3~VkPdiIFKGSOwyEHYO0mG2dd)w zn1%L8Qou)nRsw@^eQ&lFS?!YtpBXj%6v1pPNq#@-37)B`H2QK5z+G-{n)v;!vBEPZ zmQ4X)hwp6*X2aZp$G}xx>LOi4yZ;w`sivx}e#|-rgK_<9R5kgZw>3M-MMzdKUvO2V z`=u!47o_1LB6FINpP{`q)z>(_B=`0`!}BQ-ryN7JVhba9d_3;4_Hf>&GXHcy0RVV+ zmIzMm625fcY->irH-Qtcu{_uie;)GGO;{zScoX7`|`V3O^5*~fWHsMo?qdt!o@ zw#|8#nA@@XC75%$w*t*mv!vXs1E~qyysi=SH+rJxV-C>no|65mN524msv@JmbpEg$ z)dPVpr^gl`DOD6zfIVP8kwvcFyW!se0ETsmsFZJPYHRMDP#iL614V|cIrU6Id4N~( z$}BM7H}dw^7gPGm3?US;U&8c`=#6K*e9c1?3Jd&@JZ;0ODZpjbp_5gi>J| zweH0u=j=?KM6D|4i7pzrbxV8%-@Z<*dewYQ;_-YT|Iul~kHH11mX^(hW`DPj`d&kR zILI%Me}e!Bv_RdI!Uv*fG%+m9qaQfufg?}RxDDxVLV#3K0CVZOV9((v#KfRIZ(=IU zw5C_(($4%SyY<|LiF?QD6w4mJu@Nr08&f5|HfmhQP#~cmi?b@k$+S$P6yfXcY%iQI zq1YQFzrKGOyLN7UC2A523f3?}jRKG8m}W~SIiYdBuK=P&25FVu zTCM_!D4Jea`6FU2S`jA`H>~{P#?76>Ww>xJjzDF5&>vk&IjSNc3DE%D9AO!<-$tNu zVr0fdxtCtLzs6^pWITutr)z(;z-$Mi#=zueSR8H?j^7ELspg{?qIqAyCMZ|BVDb|IBt6Gms#Mw zNj+SU2=t&#v1qv_QnOf4A~7~Lo&tk0Ag_Jd_jcvQRf~{5DtjICkotEW54QTETfcg6Y?v3dV#F`M17N0qeI8&;SDf85LGhn1@c^_=64WhFIlS z6TPSh3qfjK)an;)5A#)IZ}CPF@@dp6_zd+vO?Fdx4*})$JJ4j@_w{T7k5|a^=5B2M zt9bM3{j}&|a?SXoSZ9wf8~$2m6O!5I1EC|12d)WaR&h_;ANrKQQ`nhvo@RZ#h76W; z;l~tbl71m^y2aKnKV&$4C=lvSNTvLZq99X~r2qcOA+EY=f0&O2r`MJAF9z2Gmz7r<0!(OQjb|NcdYJ17;B#@335W;jKnS;Zi&<{z(-emG2i5i~uIm z;lF)1`n<~St@QmwuI+hdd*jxQg{TWxJSDF!+y%Pe`Dg)~iKg)@uNzie;=IR5_CUa}WBzxQIS(PZ)1mM*z>Fm? z(T0r^zpS9yq6#AV?z(UT;{d{on*9W^*if?lxwQ9yW z9{omI+4|0XlEu!ntk_wY7GpnYldBQ&=Cuqzcu}RLv{^9!L)_eo*?h{BsL;1;H;$ir znXGnu*bHcg*hUU7w8<}`2EZB17+U2hec90;A|oF*SU@&SdV=qE@?7}ycK_GuivDNd z@L;|!(EnyL^?9`GAXcecx%$;R*;ig}nCW?u)quE% zX^YmPB<=zrnWP%IMp~15IO;YI_=o-x@}-nMc^{mgM#&IsP<{aLK*F*aE10fy7M2ra zv#vo9g)k+gaU*v`si-N~Oy0>0WQ}-7_=UJDY5;2=BVXiM$j~@9amB^VTVLC=oyj_4 zw83A-BWdX;KmhQZ&VYh=lK7r&*K94@XJDV~?YUyXPD3HlhXh%noRs;P~CU+hhN4%oX1iQ#k9 z-p#U97Id6?cq#i|zP5mrf)2DWn;zgOMVrz|iEU;&+dDQsVZv5Id*gE2Y6| zdTqt;!4L?Ry7Z6tb%<84jxf$!Jto>_5)yRFRSr997y#U=iLHJcB^5FwXn@mc1(4HQ zbo#`;6w%L-@OPbI=vhKp_XTk~|66n?JYiMk=!t9CbVUMAT*I?K= zVyz}F(p?D>lF#BpFmBNe(cOP=eqTUnBs)@!2;zG`p?N3#cOC|c z5EsbA`M{)^{JNCbM@z!BzoaT$>^iTqynN*lFx6k6P%LY*&GZt=Ko>CRXq>}eZe zNwjF08BMU=Bv=v80Lz`zOqJky97ZpOZ^Q&!1J#1Lfr=_4*-@0>paEoKigU^->cw|< zVB=dKy%nym^T$uM9P;G6u;?11aXLk?(F4{fP+c>*6Y-AYS$YG(yG0n>Pdvy__$VEDYo6h9It=L*LunbaYX_9 z=nsEg`e^LE5BmgbN=p=d_=MhbXseG~w;tUe5gdZ2tLk z#sd&2;PiJ;aNYfo+Iffn#}=PWhuX8e(=IT7Mv==cG#dL7b?E_r!AOQ68aOFUh(VEh z=G}D+NEY8vU>@%g0Af519I&7-U*3yl*9=g%XOKgHw-3QJpI>uVY-_ch_lHz^SO%=i0 zIPgWPSHppC#XS2N&Popg)r~u;&x>L}Yzb}o%xdo;S4#{u9Zu>}D zTqAyw{lyo5dA1~q@h4NCW|us-co6x$2UMlfMgP}Tst~1)PA|1&I;@jLX0bjKfrvNYSOjB9QENit3TO-QG6BKg6cOVf4kK4(_y6R{1PNbQQbQEs`Q=*cT`ql zK%+j40ZvMI?H~-r@Z^*9#oGIaAgbm?+2e7m#!pw)RwEhwtK7OjwghYx%p>0L zo>En&g}t^eMT5+FDLSsy73*fRzRp(Q|3+gk*n3#w_VL`ON`q{x zBq+Q=lUu*KHQe#UI+=O{v%#A$ce7a&TlaDM5{AQc;v3PUE0Bg;Ds-ngay;^}yEA7G zhUD`DIluAPtNjNTu6}8XrT3E%5L#K<++;_c?^kd8p%D}p!WLz7qQv?Y| z?|g3#y8vksb!-5hC@TeMVA03UnG7#zNxD7G_g3@VD?AU|DQ5P8Z61>U(W6K8;oR?~eEiIbG#uQnK<0H1*$zDVr;ufNkB|OMYj37>T)yD+$fO~`Y?G4T37gL6JhjO?A zE)cCos!dobOcCY>-GF(qd{W87LVw^u{_X)jAu%E(Z*2b?9jbHlvnEWuFKf2kg>Rsv ze|@i+i6~>uo<`uTL&%DnJm+8qXDX`Zo-G2MUU+Y`p{gTV0{hhUKH6__K%ls)nXR&y z)qy!OI6s_A)`x%vcgWX-(z<)8hWR z7d`sb;?3qk@wh88Mh(|h=5O3V?D>k!Q-cCbH=~BQy#A!o+I*Y9CrJt|uNIbXLp0<^ zET73G_|8CTr|6>-J1vv7+!;b>J^TBNZj)M4EhUvmC=LMH}TOe8S!E4tYE3Q)1FAUd*_Y< zSHb;PrB(#wBUR&43zgdg$?vb;uQn9(k0sRS=2;wStTg<6Q$~B9(6MGKoZ!{y{eZU7 ziR})6s>JcV7&rUpFEpwJJwOhTX1+r5UCzXCX7N1~k9c6CE6lo32xf>nN z0xYDlZj`rV(I;TIYKjA0d*IjA4TBbdEtcOm& zPv9{1%QSDyWj}93-g@-2v-YVqx&Ut~|Iu z8v{io;t|n2|0Z%q^YU*cEi*nf+t1;&hp!9YcTjT&NrZ-JCi2#5R}FH$2&(Eo(MUa9#w)*U23C-T=Ts^;B#7strhU@RyPeIzvz zZ~o+9ZJ)7JKQ`e+od$-3H+i zoh{S0ZDy*D%VbFNK@yVvZ~@wkOp1>VR#Y}OBG5Uj?;Te3Sz~(D$C!rd2$8C@#gNPA zrFKIHCUmYp@$p+O5-8B^p!v1?jQoAgjym}-B5G*ZVOOV{dFyr#vmDnYij!cBozp!t zvzQ4g2?818p7pyI^3Wrbg9~A?ea-G4d4MUYd#|LuMLv_fj`C+DSD zb$f|B$6N_8T^<_!TxR%5A5J>feNDQ4AFN2Im<}SC53=jnQ9Z6_-)M~B#Vk&v;AW+4 zq;b_J-#|fhhLU)m6hspb@j@pD40&SZT_=%MDove2-i6}}%f%|82+#*FILm`6hV#?Z zM@_C1t#@p7vzqKt{~&6yVWtE+*oVF#`4M9>qdVgZ(0tBfN3PNIPY4|z`3vR;Gc*$u zggHG3#G@Dn%qOz z=^W;jJ%hdF2t6(NU^mp7w~*p*aIE;+@$h5P03V$uUo;4rA!$S&B0>TYLtGG{-FqEPGBTBSGV^ovOpRRmJh_@)EyyBF4?%2skynuV zMcJ)AfNJ66_+$H-=ver}NN0~r{iH z0t^MUTri>@dfi`MIOU%748a2gGe@0$?Y&xWK)iTKh?0Uv7=l+o3;+S+N=`T*vlI|V zf4PMl#pDEsRvEYmrf6wsHh^#|2||}a@V$)M2yubu{MNnKBtbCo=;69zVbeZv z?S>4S+MKApSnvllfI~Mx`l6oyS$!C-ifx(lX(oh(Sx6=3|L!UPOYf3K!aJGpZX2q7 z_}R2CZo_1Ij+b#1`>Wkfi@Gv>aUk?KPyO#$l7x)$g6t2*FtQ_vp^a1)H&x zbFv4~>WCih{R@Q-+q<|W41-`R5H49~R51s3;r&KZ3**JpKDQff^ua-V zRwIw6@jPd!*9vD_Q|)aqe~n@@6y9?fvlE9#Q{X~W-?ZGPI)5gH74U!;qoZd;yxM=} zB#-+|Ixl~P#ov}X`@aHCj}Gou%IXu*h<=-nenXehAhSyK!q{4b#x?mW&5rc=PtrV{ z+a{OI6vuhamf75xFW4&_wMfrUzP<=e9V4XGYg^v*5#FnPtj&!urUx9i6aK2kccu2T zP)S2c@XO=3rDX6wHl}KYQ^K0nVWXW5rfLmp4)m+1mHR_+fnKDm&c%`osZtA>{lcsJ zDxz^I$f?2|gS=QEAtoefOtkFx7|-k@V{kmb)H`iz%o;pnJ=5`- z@Jnynm9b+p>ge2elz#U-HV*lZ)n34P5?u>nK65Jx0Rl3W)4^0;i zI=BH8L{C=Ax1?`E?B%Rv#+V5R%{&(hi-id=G$y5-Ht{`a@Vf}31uUCIBK>GZEa}dR zZO7!|zM=!lC5JBePkMA*=dHV8ltga((O2~9#UVfFdF|=Qo@jg-UNMQh>X#c17Iqj| zQo(j!_K6i0%l|ZZpYwnR()q-uN$6wWi-bRBq|e{0&)kKR{Th48OEpG`IvQd%XMU=5 zXPN$@Fy7~^eXJlDO62oi5}{)6N=(7y1AF5pQW1n@**)BvbBw=cE6wn6-L`3O)}YLx z^`gTxLy2@xdd(}@l;!7*<}e~j#`5k~wn1^UbApf?fck%;@7(jTE_OZ_MuuNag6O|0 zTIww3RSL|iDeUzb4-r4|k7828aki_uUXez1?Z4mL8Xy=_uZzAh;+|nPi+`>>qB@z! zsMF569#p#%bi6A}rg}WSmtFl!T`}qhehk%LCQDa+=7oJjT&eDO1n7GZ$}2vfP9GoNKfpt3u6gp@fwT&`viSqIbf^> z`35a+KNvk23ZnX&pI<1`>_e@_cgLu#|IcS^G zc+O5WFi)26XS7ar#nzlr$1{vql%l|G;iW~TqGZG6TXaRet}u3|A=RXpYIv{zG{$~D zmA(>1JlYo9yxVvB=a|LuDac{}50@Dbqe@YmP<+gDkbNM0+6y>Vy6zANr0ig9i^%e3 zsU4p%ObCh;$}Ot)x)Oj4ZlBA(NLg4gSp#y}8h1{bwvG;mYq0-!hNs^E9qr2MYWv_h z3bne!g?Lvso3$3;zOr$CcDBZL7idv0kUxG+VVkDI7Tr`pHTbU$D{C1Jvi=RxS4WQz zH|Z%4E*Qaj=-t!#5gJ)nZ$KWG062I~>mfTGFBK?8d;*Gw{)(FGd)HlHq>|~rE9={6 z-p`JB^!a07?3WOg5qWO}wq4eb`{0jK`gioEYpgzTh+$_E;UVwSDSe>=nC=OjO$|`Jo2Y9 zeY1#Tn(LTDJTi7wub_r55NQ{^$ELF<2I%(UcO$aDzUMf|iQT#cn1hO4w1;uwb1ZQ6 z+C}c4=4_2xMPh;^!x>y)ch)|TEf1Kg})MNZfK!W)n>uwU%w@%z=_cu8y z1^fUbZ!zR;#NJdZ&>HTUf=3`W;sy-8dmo5Z8}b-UmCcB^o0%Ddu9%rKC953!ZAG^F}1rYY1X%0)Eih+GL@Q6UWjWz&THS zvL`P&Mxz6miQWItM}y%@zhECor_lJ!(xu=u%}D$!+kq@HlOIkzM^8bh5Z0u|s)%3a zYHG0Jq2S+ZRcIqR5RxD61hBecCbC}8Cg_f35=LM0Zwq9BOR{ROJ2TZ1w9Q%#8vKzd zfN@F2HR%vQm{i|Qy(my=1;Oq&TCTfT8zaOOcz+V^F0H~Y1e0~B{e|IhB@^^yGnQwBSSZHnWs?)PX~@zI6mqe2}mH`iLVe!q0nub57R zhuxg0%{i66r^f!NT`MtaIq+pYSjFX3@Esp`(x~?M|L>u$$sBNqR0+IV^iz87wsC)J zt^$Ib)vT3Tc%!d7l!FE51K$Pr2aHrpBS#sTxpme*XzB-6`U#ce*ZJR&XuA_V~8f{YjnJ|`tmr69Z_qqrT%>G?W!-aR}vhfDkyj4B@ zh-~cgTE~s73N9ayxV@A_VzypV8xL8&|JdmTYp|PA0icbH0*G>Y_Wsj6a6rof9s&Q~ zGs(I(-1zvY>-J>|f2}95Ihs5CthRd}a0=z2i~XqQ$j!rjJ5sk65MW}eyYge)>TeN4 zAZ+@et4?}%@p#;A5zTGScIxxu1F5Z?>Ucoy05s5eFnF%Dq+EBaZOFBA&%7ruSqSkU zNl_iLqA34=y&N(}y53Ex?q^%1-sdAv0UruMP{@PX`~Y0W{$1G~JOadCS4gJ(KYFBn zsq?=JF>*Vkr)c?az084IMHGqIU0;}%&J{A#VqxN8lEhz7zeSw()if#W%y=UEYsc&@ zvDDTUEa?mX#PGVD;XMJZlN;9junpY$N4W{D^QI`%9dT?}X6W&F6hMV=Q)IfIqRzaG z0xswtqa+R{vZu?3MSt|gr@^``d~f?DZwCNPQ^DBll&rn2?Uk#m5Q;2wSg0|Anxy+e zngoFw0t;kr1Oo`A(?}}Bu2qffyR6vHxSkI#&z~6nVd9#0*E*gk02P#xE32{z=6NV;dw!1zAoY1~9XX6%?u>Xm zrWK?9H97yoEUW1j+~6o7q?w(a8psD5Df^(700@YU>l*jLiIH&uB%S}<)=^?$;w~>w z11$k-7gz@7xu1dwHSneU!YW*toX}i8@~0O@*P$id-GH0UUaJbP-#XbcRHM%q*ee^AH_f1R2)iGW^IMpA zQ9GC#ZShP{V>(u)A@4N_AEs=;LdP9f2f4)r5Lf`_hL4DinKW#bZqQTR(k=4;!cSAg z3J?*yV}22XK1ZLl-CGA;t$%rP^@yU!5S&Tp<&qu9i{5tv#<%2Qo23D`O zPE&c*?qmmkxqp%Bb@uRdcRDU9Ik^j%@uo<6tD+KhAS=pBpmodTMv*=1f#sgtTSKthH3jn^| z-WS#pj5s-+Syf#$b8c;w1K zL{##&`g+49zRa7Oy*dfk_kf%o#%9h?-kb14v#DY{bc!*ql=0Nh`AYXuCZV5K$59~| zn4*7<6+lj@D$YrhXV#0SmC0X7%Kcsb91chY z!_oMH&W*7>6r-ptP!aD_*9y-$t z1^pcVD0P~s|JZR_NR}W)S^8MgltB>y?uVYHBQo*gPOT#` zA!w20z*Q&9sQa4OGS9Om)xyZM>&`gi(0;|MBI}*^zQq-YhvB9ac8+*YffwKL*dM-k zZHoG}E`^bR_B;gAfNAZ%Y8WwWK_Y3CP_bL7-Z#Px0**1afD7*g3~Qi7#O2O6$V(@0 z0u-&wcD_Np*+ar<;@R&C8yRa>m*G;V!{?gyYN^XL%kb8bgAXIxHBbw}-T3iT0hMhf zwwd7J4|h2Du2|!!A!|cZN_J}mHPsVCSxVpTd-naYnUuM`Id9~b%-rk^BIxdqTkDM% zu$_7(B_)+10W7)FK`hWF;%(&ZWxx0RQ&L`lJpHF3lG$ozjRPAAt3S9h=5Jf-M)|A| z8odIH+Xqj5Z-KICq`=+`%hw&Ol4uVjXY0R~z(qWw zz*#2Xs2n&6E!%Ke!7#i&!7ae3j=lQykcq4>J+cMePOmmmZBJ}4(P~#BY)9m5;g-3E z&ac4f^2JEidupQt$O~$@pK3{s-(SQ$fylDocZ;P2phNW^ zx4)CkFcsv0k69k9P4wIENO#8{o6b3!^lcfIADW=y-!gT7z_$Ft%B|nO*+pYGn-}Fk z-%N+~gH1q-`*jghM0|zJ17GK9e2-p@RgN&$BTKPNY|f+wF1|GwtvXV zzS`d34+DC5MR3f$JR=T4xckcCbT^ob^1;?+BwZFeLClRe_iA&d`nj-(h=zrQMFKhh z2|hWl)mVWNaPb;I(&g#?sLb-hzx#Mz%+~&gMuS*m7;E+9H_h5HzPCuB1kn$K1RLuL zk+uoLH-Q+Nm7OD9!@a{E(O_eoP%MoVE=)khx6n>p*l*!p2GTQcdN4eTfJ0Re$+^`P z5c41Q_bHf_?(a`vZRmRWiTNBIH5+m zUbtwXHWDay6PRg6f?Mm5tMiq2&&%JZ(u|aT{W_)SUXz;-vCXo-tF`crq{=S z*~}pG2q&+b(_-(z#n}{a{NpzM3g)R6)@YS0ssksVu~7(?VJ>h>9jg8ow=q}&T0}SF zg?gc-MR~Grot5!Rl$FTgJC=(IRD_ho&4np+7o-SfzCWJTgIY&?OKH11pOL_C#o_o< zjzZ0NaOWF2AfFnStv~QWDm~S2*sU_JWdzLV{C5@lfXSTNVm^JS%$Z5T(vR*PDGC|q zp7RVDK1qXl@8oJ#yVH`-Mja_qXqJ2;p%QTO{YWDR;`8FavGy1iD&vwmoqIgdDSa~e zc}r!`J>M*ft=2W4m(RINp`rf~;D&_y60bIdhPbS)(yvflv#(DVsaKNZBBaC8POq*l zn-SMD6w4Shj*OQu%((@gI2(zV^lKL(K`IIKscRVPgA(NU&7L+$O^gY_73S3nruR7H z_g+52yJ_yVORlYUNyC9h=>^EKlf<@lsN1KDnp0?0$OU9)x)!w%f!1^gi|DQV} z3Vxibv@`aMu#71wc}Dfj1nu(b%GwB9@zCGk8f6Sp{foTw3>55Wpn{NxK;Yv!g(fc@ z9UXxmg}rBl%R^Cfry5)&z2DeiRG&6Ds;*Ebc`n@;;O52{>|(pwl;L}#(<9KkJbxGS zraWJB88Y(p^WIGQAKU2$5Q1v`aNilww{`FT+MVbp9GCt3ohu)8q=At|GfMUXLb%_7 zSk^>2HR6R+Byh2)c_4m4wJz;V^Q(fv$3A*#eX%vzlfa}Hr;v^GRqmMw&?vzoM3V5= z`NZxTn??!=cC@1>EMAs|_?jMaBY?NX`pL=W@cEgS65jtQ@u1;1!-}%gjb(pG(B>6B z_Qz~G-Q#Owa|ZO}OE%}A-yS@>LbqxWZM82kRnROz$nP1iSRbX-93x)EyU_$Ekta_z z#Fr?v7by}Nd!Fx}u#4ePjE1D| z>#8G(e4-(BuqxNs8H&R9cZ~8(7)8prDFc%tR{mJ0f7X3vj2oi(>7x%DnoPg^U{@>D zX=#C7_1IDJ%+gN+&GhX(F=?N1tjh=|$=pb+f!+g;Pz1HZ^Bua;;_)bB;}kJBi><27 z2eeMf$F1`~4_LRhY^I$n@pliTMGpw4D&t1Nlb#9IL6ayP1!9mu?RiLgSNbM>hMwK} zz}s%s84F=FR`1dyxg^7B`)OWA*kL7YD7!lf{{0$AbQ56Jz<{N3j93Ex0XbDql&l&B zPibW9rd0A$8 zS7@o?w6RS}OI@yW0Ii-l(g#5O>tN%4b_Lnq0ucTXTQ|*zhsdY)dmV9F724ts&eTO; z&Ku3}J+r#(w}#?|$Ixud!ucesAdJ6_cZu|%8#DYy#K~n=Y=GwzakZ{3@eRo3vVZwD z^~Z{GgEhbqZQQ~HtzG15jC6OY)lUHTi20^PV!0$$^(5{vVMXf)BauJoHL4dIBIUm_ zwZC{$+#I0|Nb+$1Jy!P&1{N@P&2?OXwOIF|ts45nL_p$Tq$qv6TkmncWc@NzDgnr* zlMDoW0$H~_KjR> zRcny(+Pzf*t`eJT4IbN7#d>FUY!IKN6+J7Ws1?pc<7~?7Z!wRsD{v zZ?nN0{?=+HjXky4EL3BpV<-VB-oLq4(Eg{QR;Zh9A8QS9V70_{C(_kbqZahG&d7UV z)imb~?+78W)f45VtJRCA%XJlCDrCG4K5hwg7aKYr`Kg|`H7dXi>%FpE%465cc6beC zN`H6xg0E`+Sq<%>kGy-Os<_ksI7;-z?nPreeSB_y7E_JX=X#?%m{N%C`ZnFQbg4!j zYe(-Hbmh@c&9aYv`=PP&Z~E4Y*J}F1Krr-9NDKr)S?D4=^EuVbtsGPfQhod4sSa(*uEB7bD;i^SV zkT9yAbmjTQdwa=%55G(^u3I2)jB~N6TzTMy&;B{7_LNPh@@-P41VA2fF`&Tiv37P+jwF9b)>kMm9mp zg)y0!oHX$=-0Z~ylC*s}gB0bm8uSmm)M4Xln*Pu{SyitJskC2SrxXtdu$_ezW*<}B z{`4B%7k|W_Lg=#)fFmCXtPD&Cmu$lcCt@h@Nx{uC6cMja%tGLnMC03NYfg_??GEA_ z?$0LUHhEML`b>iD`sy^(^ly+A-K~JO+K$z4@SUG^w!`>D_V)H_Ty{czYk>35@j4K< zEmQfLLELF)1R453AZW+9VmLXM?ouXw2apaw=O$cmPvCuzXE$|^5r#$eB{Ww=OE@ym zJ4>a-jqw_UfGYx1r)BFqQh$COw{}cj(4^Y|M~h2-sd7_knO*t^58AvA_2g^VdRjqd z+b~vds$}ZC9R~-;O@nCzS~13P%M$vKe7YJi8QTO3mKsND0IdD@0Q2v56H^Twe!5>3 zLGV0b1;-P~vkeqSV%%_fBRb%HV!I=%K8Y7=xm}9y^kgZ%Xg^SNe!!()nR6zJTll1_ zk@O2zOX^LWqh4me>b}V;Y_v)xr5k{z&dhIq^UTcs z-0xcNTK+NP!p*g>>%7kRevjjGEV#7Xy^H+`>j1p?skz*@o#G^j6z|ZWzaKMT0xl|T z?W#}elc!80h0c%15Y7Ba#Il-2B~%a_+QptoAt) z=A^y7JF3cV1L#hnGIvdUwv^;h%<3`ww5ug6MZ>TvGC*Wsq3e>Qh~*;82Iwfyj+UOV7E5t z&K(h;BUlN83(@Q?MJT5!suY>^eSE+d-0E8IR>voxvczNEdB;Kux;5dP`MHuP=q`UW z$%~etFKq|Mu$eQZg4Z;}=Z5k+3rAzkg>-Nq#0ObZ&9%HvtZBl|jMtuCCARZA@$#y7 zj_JiHcMOYz#4_$fBK_V=xe&XxK!9~%RjZ&c8nzsGT6atfYkH5K zj5}v_b$M~lIpx@6i!1r&bii*TD-t8gjRY z0$riqpG{Jr``Rp?C-ivxO+;a(?ebCvVq1eoD=hly&ERJ4m5g|yQsK4esHj?{89ln! z#cS`{+lzFfvtH$pN=QgF!(%IEpdxvvE-F8az-zsx%pj|j@!|v3v+BDtGe?N&gkVa6 z4qEbL(%V2PinPhwSK#{Hy7x(VMo+{LEP&^iK$9R7`P^`>>B9ux8EvM*=IF}ZIdZ)u zA=nL(%=vSZTE?XvO5xpFGJ+-qqa1_RN=@ znSXjs0p5%r7*KbYOdcaKKPH9@Sx`Hhvrodc{l4B9h6!k*eYKQ&G^o>wVCMng_X6PL z`nBO~qKONLts?bEL1t^xxGfwqO{ju0;uS7mKUX6rlddKy9h!j zTnZ4HV!uHv%Kp$s#}w)pzA*3$vz@w?V}D70{H`a~`=%hJl{j3ZhQntaxE_ z+7-W?hUk{Kb5#F30cFYu+*uIn|><338xVBgkZO<^8ujU z&}Rf^u<6fEFA^efJVn;H4=C89c9$Lt7prc~TtN26d#2An#a16JpLqd8gxm;fAD7hx zQ!vM?vp0QPgp016dMCqou+Njimex;=u-rPY8N2?HoM`7xr^FWPN8RLr$xU3aFvpCN zdP#VLBFMdy)gfN-Szi0iANfkMJ1Gyg!}!YrG$#soc7-@mg)CMNbs30`p} zU#@#Pt8}yd8Ul%{VF1%JJ&W4+0O_o2WIB3;E2()3=a-506KAMoMq*>NxxzDI4PvBk zl}5sCcIG4^KAbuaA7IyE;78$SnTWtF$pc*6>R)bO2rIL#?NqjmJPJu!tE7IbK%LNs zVgIH66xven|3ylm+Y>eeA}Kh`M%l6z({5rbq}~P_(}fq=)P?|Em>e~TSFO!j+uWX+;rD485_c;vvae57-mcu+>bOt(Ddj4{}<)K$4a z<0qWj2`;%Q`}UKTQ#j7<*-SzFKR(W5AYT$>KdqcU%$^2 zB8HF-S$0Bc`V%JnT@_z<7FbWbawpWRQB|37Ki{D*G5i6W|y5^V*xtpPCl~ zb(4l7ihvJD54Tcik6PIS0QnX4vExzO@DA}^7`}a6;Wwk>RR>%ty8_GN+fb8{BtEG) zx;csq&{WZTF(E(BTeu@s^4N#~Q6=MfM-~95yKhxj0d& zjuwUwDR?M)EEeN~GVtXj1T#GK3>AzQt6G&**Q}8~fNid+SGeb%dItUB&19V8FRq<4 zhxPGn6A0Ym@mJzVcrHG;muvJI)7q$=Ni!VT_|_B*uz^^w;_o14FO7_xT6M z-h7yacucIUp&31J@V%H5?oO5-dz}i@T4)tJgl#N;7Wv>(^0(b4U)Aq5c(h$8{hmX{ zNl{!j=6Z-C#s&2@O{_H~0AkeMZmMy)951)r8=zXjYYgT!lg5sMo8qhj@C!TZKEM)_ zKmpaN#>qE>V~{6H4|SoTwGhxNwRWHqx*nBA)`uJFFmv!111uGn`>kAntM?my;r$@+ zbhh23mi4?e2)y^~IXVo;u_|$SB65bm$~5A^=KNo{ZBe%$ok~35b~x;a3#Ye)?czF1 zUl!(P0(BL+db;ES-Q@SO`ADaEN$JZ~8Hf^4Fgl4zmPpZ@y7#IDFZqRt-Dl*|em_%9 zDs&^+Wn_a#0+1JGM^ad~X^ukQ2h)t#bO9;{Fa$+7Ej_mUi|cEs*OOttw9?@6WT%}>mq)f}`qUtby*&~XD&JSC~? z$aewoY8gZ7QG^)SU`?rL=KkMU(>w8OfrO(cW;Pr3DutY?uVxk79?E`2EZbFS8Rjd? zb4qyt#JbMA3$g_jp0YNfMHuGNS+;Z=d3iW5ND0dmuJxl)OgJv?tQjUCWL zi|+>K>bWl~d67bBRQK;m9%%9{)YH(BOS%(571>p#VjVh@cO#w-XYY3jA^6{b$a9H& zb0vq;?+i=-A_U9!xXy$9EGW98pMv0$uQq>ssUl>6UW{rr_`2GHEg8FyNpk|>Mb|iQ z|5A!)mFozQ-Df&K)|6vScmH~G$w$^`lkaeW-ml~|b7mElU-o5g**%p!RZVBz=m8J* zrzdq-o;vx~GE+vx0TfPDFB29DgQAOHL->iY(_&2kg}cfojSD3xgfvecK!*nlChw!GyLO_ z_aWYv0f$_Yjhr6)oFS$D{KGvtaMZ>R{>J_W;;ZWB~cQxz9>T=p2f+U&)uv2^=9!iNy zwRzFnnKO9;*bghTSbSR(CyKeDwA%+!nfo}1$@TYB1kvmz-l;ghW~RV!2cAG zJME#?I^t0&x%wYI*$to3j)0n=>|@i2MUyMQ{i|1+@#YyIE>M$tPR;M^!H#n#j-j2Q zuC!!x|H?b3$BBO-q1Cj>v=`w@ze{6z8o={rPdyc-AIt5XAa=NICe%7FqDzrwn_xD- zewOW!(8_4J&HUZ-&uIW4Y;TUjV9!Qbmk$Vk@3cLs@Zy6TMM>jRMV^zVjwv2}XG6`HUc`W1Vzx@-h!YEBfSBJZPov z#-pI1PFdBp3vw~d76LPd7dx@k5O0azETKFE3~S=hGpDz!i8fSH8c%BKOPO0ocXEQs1;~dp=SAK&H%i)nJBjN z$7X!a%^-$5sSicQZi`vx6HA+mOX($H04QKLsI||Lui}@1@P}Eu2dfHT!nY*I^~w}xB6jrketscl0>nV{jf ztBR^-Lh&o)j3Io|Q3@GvY`Z0DJHGodD(61)yFSk)qg8c)iR~snO-hM<3tdq0;109G zN1xi+8jsnfFNm;kpo=rttPX(Ki0SjJZJNh&iwcA`)E}V-k@G*4yZ`v0b$@}|W{9uM zcCHNY$P2y#gN45hQmkCVTk1IU!Dzv9BnW!(fHP1Ya^08;)G3eTbAUFHit}xqL22}z z6;~b+zW%Y-duj`%t!Kr0^OPSe@KZYTZ&A%B*62t>ORw6+GEP>}Yy9YL1kIHQXOSEe zt$xdTtv#KJCOGDcbGLoDN$F1OQJr&bo42JQ1^v-umCP3+uq1Vz8SJ0HzWZ&wp(PU- z_TMz7NyPEmXBtpEm6I)<7cW3|Jqup??7JL8#oVv`P*zJh-}0WWB;~YBOZmE6oUSAA zbkg-2yT7#k_eY!Icg!fUPgXZKyF`VG?=W${_w(Dkk>TGW)x^CUMpy1^Lc&pUbGK{! z=g%G2+&YB)`cTTvcQOhfQfjKVfb=AvD#dNDr1{PB6M6?efqflu+Z*NdhB>GDlV7zjntoYXF22oOm2aA(3YS z?AK|W4H-M8el3;7Nq5BB1=CI1w#_QFm&avR*1{k$y`tfYKs#YCOpC*~u?h_e{HPIf zQi98FBgdr4LY9|av9~jn5J?NYm2ein{Rlmhm3eua0RYjhnkSfakvo~hI>~4E1@;WL z4wY=;$TE5uWuVOq#rz{^D5)nr)7<{L#$diiP4GI{fUgx`J?l5S*L|srH@uDuWbiuiF&z( zRAFQJF(*wvKep{Vx1(lLhI3ISbSK@Jqj_(4Xv4{pJUM^!vUFBM>-zT-eD-?lAypVE z3N{uf63*C;CXh(8(K9i|@;QH~rw54kC2KaF1j-Aw72qT(qD8LQ*Jy5tyk8f?HoH|h z^*zjeDTDI@C;qR`>ARotc>@UW;&G(VWjrUXd-j{UWcSrR*C~w= zGnAqt`jVn3^zy^dR;1P?Ss6oPO=Gq*;VOWRVF?CnrZ;As5)P#j~3659c zNc$riAyQyS^o7lmGbp-FxtO_D0Uc)hSW`53W#yIoLzJRLpeok26ud1hArqbsltfKw zg&x$ef}2~4Qw*8rg#rstn7K+z3moQ@@8Kf=3#5xoz07Q07-`PedowT2^eB;Pm$@2o zINU|DO2??0+eoG~ho=?jX>G3U5@I_7t5Ht@L)3YDYz=c}>iYWEyGWcj)Z5NLH(YgEkweV^QAr8ElZXQ}^dVWF6 z^fv{MM=MCKZ|K{sk?|^Bn>+F6s|aP7xzQ5@oaQ+>e=t{SmVYCC0w4Y5jeXq zb`V8;7@Z;PYXunARAe3;LzPfY1gLQKZuDJ*TYfCN-)Xj?B@k&_X$qa1!f-m(Lnhdi z6?(kqJ$LhHhzF8KkhL1JULXxnSI9V)~tv10lpc2w$M&Ec`_7aYt6L9n)!Xlf1&k8hk(m|B7;)8RR^Q^F)P3xrt!vKdYre0 zp-4}AOZZ?BKI{cT7$;q<8WxoqKVRRqZa)qlBQf2;ARgLxcuTn*t_6lYl<|b!eqbp= zx|)6$lPZD%N%Pnvh^SB`QT3PQHZ{t6W5N$;a&EIZ24M)9T(Wq=Wl5_ma5Co7I{F)| zi;Z?3E|N^|*gB_-f&;EiG{r)VPT9eu&rC|5W_)%Tt3S%D7Bu_j(!zzJ%L~<7)%?R- zm$@CM+>~qOywNH%QiLwNA2O@SG(Qhd2ZFpk>q81x2EB-kp=v01HnJ`ACCCpoQ~Br3 z!H(gmrQCx=P_9%^!Zw}yvI{jQ{wiUE2D_T_ZkuXRATh?nMF`534IeUn94cWOO&xB| zBK)b&XQf;|b_4`ht1Iz@gE=x(#6P=$1>C`W)3|Tr9eG;b;dT6luvWR02wCQ~no4y0 z%|UO8i>k#KrwN_O32ra#O}wN)Os5fC?JS9b2&9n9ro>)xsVc%kg1`6R`}$q3*JwTW z6!z~bnUB|Bu>H8~rl`9AJRk+Vd)2lHY;W~`syYjFo!Hx(A)b>>l;7uOZK%xmok-_V zTHd=+v|`!!?URe+x=j2T^!Ng>P7+WIF-YQj;+ZjS2eLaHJH=lC^u1l{L{PA6eP@hj z(F|3hTmD;b%YMnD+=-FqLM5+@Ys&GvM@<2cB~JKN{3ydk;i#7cUM$|l_Wt*kH}g(R zOv%)Y(^gE(V4X|~zr@rtsnkaa49s38U z%|Y!>#kN{$k$X#A5A<}f*J2_~#5Lz8cHR!{#`2;{rr6{rK6^TYg}SgKWx{5! zAxmEt*^%lv2KO`Fp zTP`)A60_>0So|^`ipMh)q?!;ovvWXl?y_CQhLJ0HI`iSZ<}BWEY1SwH+}Gr>LY20? z7@=3~C-JFBG$;cS6^nh3X8S4jJ?8DS`}ttovM;j605+C_x12;#o?IR8%vY80N~c}N z%C|Q&05jX~9ep=$qLzam&IN&xj}`=O1Hmc&XCMU3HV=Bv2c%4s53AGx3jepx=eKH4;q3sIXV<~`*C5v{ zGdJup5|4BvC`R^rYxkV=xM~?irq5>z*)P@6sFtm17x?cxJ#_ao?0BEBT*x?}zFh{5 z&6>Nf@)T9pASR^PFc7Z`+(E!R0GJg*j@RGn?u0>{cGH6N4A+3YR5rHWH-WUDR}%l$ zUkwDl)Uxv6yidVxLyh<@x~jpBKsl?7GqFYGFC!R%4(j37HNImkjDEds!S3e^xJ2m`|5q=%<+Pp<*hv<`)LnO`HZ5+GF0{I&mPkBC|(=dnwwmQTC z*;Y3EgFcICNxyQ5r$1c@0eADGDCL!AG5qG`@hxCeJRs+YIK34ot)R{w{i=;u|CJ}a zXZ<8bclT|~8@cnN_RoGo1E4e%>t63?gSZRmZJUQ!vIDWWan+InH-cxo+*QoR?b3sB zwVlOOK6^rM(2p*t;7_$=%^PL`!Ut9!4Mq;`;8dlfmuc=%2-cm;bNA>G1DgheAqtmU zGiQngyC=PCbov%nS2z`i(GeCrqDb$uju?F}(-Fl2kz2yMx?y$%s@_}v3)4cN%O3pd zj1Bq|BtTCo-3tDL^PMO43V4HlIpy4F_~`zaTAawPth%+ymMs`u^rz`JurkIx#Rp7C z(3IY091)Ek1|c*0lil&4 z)DrbtY%09KCWEB3xHJWndG5CZgin@5Tvg4zuMuB~(8Rd%#-1NK97d0X-K1R3)65rS zePOH})BdJwN=g6S^6nJZ2yuU8Ca9RSrRZ`O>Euu(Q=Hu>wHS%NaqF%$pTkBX$Z8#U zk44x%(Gg8-DcBUcr_ox66PvGjrNCj_f4|FA=^elkG=(|$-o)+mU7l)iQ9Na7!dp~G9dk9&W$Q7!@N%$7v?2BMW zBN+qHGSG)mltyZtVY`*G#pM7UzH{1#AfiwIli>YWY0vtmB9wAYtbUl z1}ZK)wR56WZKUOZI6^fGkkRU$Zoiuv6NujQS}i`ZL;J~XpLEi3#I~|^^kGcE8xi(S zQ*(EBHyI=?1OcHR)e`W)qykXzr=Ym&m54*Rot_6OGax&Y>C$A71zb`Z=u8`TpdxeD zfA^pMx08ee*#d}JrogL8`FY93Mb0mV8|P|k;g;(l!bTL5M=fBZijDOFc0hmPE40W# z4G6u?^Xqh;5S~cL*vQ6CT5ue1A7t8%@Jdttn^#xnm|D5sJp=B;YEZno$x9*e(|wD zQSr!|9>vR1@6a5i2wr&iO)GPr4hU7^Ug-qYU+(a{JX>3432wRJRmDEo(-BjLKVhQl zPg1HQw269ZrMu|1b{DHVvY%(KWdPycT}L2qe7u0JKV0zuDexjecg3NU885ShUj;E) zdrm|PxeFo`@K1IfCo4aFFEVd^;?v-6y}XBJbkNw6bqd`sRTZL{fA*oF-tLI6%XCkB zhWmWt0M|M5?8Q4GD|=#IVh!G|-_;T-JB z%n?L@EA5sscLq#%FiDoe`;763KXEEDRM6~uBZ`fkeM&m9x$)9Rb34Y}dl~IuUm|x- z6jtGOH0ii7kwmw-2OqAH{6s6tqZ?UAhrFe}|9DG7=H8Bd3aUwpSLL(uqpG&kEXIkM zmeVbZ%6p_|REq7Dh1}r+ca$g~Eb1%V^7J0WknJ2-#D2`TyNxps1EA&~47x9;)21;e z=LQAqALU&K#dL#EZ=6^H=isVg2bP6?JimNebhP~cv_G?gr ztYCn|;;A~Mx%whsIRznieNi%hYF#|Zvv}iuKmVeAVxEL4Uw3|B-5dE!8Q{=bJk7h1 z>~B8iK?qQ^+oQBLcb(vo@|d#&$1p+~(9FR9cbCV)$pD60cBIR>D_+T3Pfcxr_ub`6 z0M8NW6VLTHt;ukn`ZxxGpHVsWF7(ShT{e(74}H~4xMGvZrcP^$7jVtAt9)*~ z{Op>F$>0MBr2IIvB!B_)9Q`Rtm?j+7xefd_7W?z!P&o<#v5WBOS3@vCsdK^uf+@Uq zqGKE~&Sc-NT#o!M$7{~I#X5StL?^LAd>YhG&Om|x;fjvdM`E{!7s)!keb|tb;+*t& z(I&_mexJMI33;~7y)${hWYcGv`cTa}Gv&B3XAX*cqM#|T(jv@qxv3*kGWk@RXPHir zq(O87Y~V^(x7F+96IpFQ|Ei|xpaM^XF@@3-#a|qwm8Dr=2o!#-Q=xfz?w@M_SiizsAmCuw+9j_>P96(#rcR*&LXJIE>ECq5*1C`=h+NcZPe_ zAw{Do8Mcdc|0SzN)#9U(15*BYIW6Y~s2J6iA3_s68<_&@ZNbIb#@Z3!35C7Iw0DBe z8|0@tbWb{ksR4Pnmiyu9^5AgRQ{W%UU@wl?d)V^jY5Wb7(Qh9S(8|4qwDbtB!5Rq} z7hs)1j%Di4asa>n`AlD|%XGo~4y!tnTW#@Av$!JC8ObpY%`k|e)+ff_xjAcpIA%)B z;*VKtwQicXce5@-^Su|!E|&YZ1OMdr+mZtBxz>aeZOGTyjjWM?$5vu#{S4ZxhAgWRn!;wO!_j2RVki)J4Q#;{T zCZ55nFBQyuX?6 z$XtsMgJB6SA{W4}s-P+Ls>p1aoIc`n52xU|=~3*QPZbw#-0_}&otnow*cz(y+0QnA z--CcRh3U?Wt?6>Vw*=qTwUAjrcTL2dJS%P!q^y_zu+I(v;?@^N5wq6UP^1%lI5dPO zImr9gu!lEOMCJ|p0AKSF+ohZIv|sbHwtax9aV9{ul@vccuFNr7n+vjga)0Zh@uFRO z^{H*M1K1va*>Y2RsRpQGsvFy>py#l+Q;|W*>ln8Vw8~l4M_B>5(ieW{I0rfb62Y>5 zJ$ef&hw+w;gN1+ZQlBf37N>~L4#0dfNSvs(()c9Yf>=#yW zE18%$cNJ97c3!=h+nt9CeUfSI?pWu^a}K(XPAs|c84(7~`?X+6L!BN)^6KJ%>HRmm zUuryPV)vbwx^j-AiQuzLTt*w@PRMm>mdWL1arXL2^sowv0CXu+cj`I6*{H)iR@60p6y!2P5q@WII3zgm6_^rtv+G z<9%2G5?gUyo%$<6!!o5Jr#O1eF>`ebKji6D#!+Kj0f$=q^d7k^xqy#L#bGi-2Y>e& znu5m>y5MwYyDec&Jv{t`7QJ_YeZX$sLZ{Z-LSiB#@@TH5mg2-CqRVl4z83emUmX!} ze&<_k)?QHj)fE)et8juIaJ5k|MpP#UdbqZ0A3LoidnJ3zo6 zKc?Txq7z@@tF}|FyE?ngY*GUbP@*pXv^B>E8aa3T#sK~)|CJ#V3?s*tQST~ygj}`5 zCM_UO2fwi2nh^znpT4vTX$Jgb++aDT>`!lj7*Sufr}I7NIu5?F<#5Mukw=a1-*KmZ(rHZRoYOrYX4keA1C zc8|k!BDUognUwS1!lK?wzqZR+Z^?la)1FG9-EBMywoig53xtA@rT2m>mXlQ!653TQ z7Y&|qQdz(l=q6XrfO-P&`7~qZ(0tkh0SxxZtTj zxmnzb%Zm9H32>K~DCf58RaM!grQ^ixj5@(}riP|gj-b~(r>C-Nmkv^k91%KCa;Dja zfRuRwNUmufSL0R}FPoy^8#pSsTP z`wUxKiV+=yvgKe6mkKef&I{o191chKN(9Bfzwbm3sD(Dtj&b(EETDM(kXo(qf*TwO zeR=KHf1DH-UNbOaq(!Izb%7$^a^AvdRz@&aE_vJ3*au!-M+07N`&5uSx&qr!l2tzw ze2HFH8$>5nAf^Go#}&VLanQ>*n4HA}-B*y);BdW1#GrNG6M&{&LAc?gS9ueIIWc5D z@$h5-7g3z`@=r*(x~DbW!}EyJj?)oY32e8wBfTO`1bW1^DZ)f&m7 z;=4A)p3->X+YhuHmD*55VB-!H;Gq#;t9?C6eJDzcH#4idH?*s4^Nvf}9Ql6^=ZQf; zDrKegInzyjzC-M&A}axVYqIAolV^QxSpnSk{o}*}(>I9S(^)59Y>qkhX~S{jTwV?s zbhS4(`=o4LTM)QkAHjr=2K}c~d=>^-C-bC>aYY6^3cS$*+W1uOvwU! zF4LG5#maCc#t6+E^k@mnOAw3+8x%XH8g+iZ{_VP+6Aj7*zBzoJHNH-iGka*E?k;xg z8HJD(`sb78p@RiGUT#W)bN_uQXp)oX6^L+J`&o)N^7*k+JWB%BKo?E`nv*sN|Lp_b zr&!TU)gW$9-E=$kT^_fwmAOmvgZ+#7xwt>v3jpwb3RDoh}or(hDutq1gKg{GG>% zp<4Msjd(5eD${$vyv(F^9<`YF;Kcqjvr_QhBnTt|3iv9YYf2AN&;-Q=ngn3o!{&ot zW_xXf}W`t-WY!5)lu3qua;7vZ; zx)TPyjL>%hs^L!!<;F@(9!u!dL`%<5?QG8(Iqc`ZtfO7dC|7u-ao^ZeH%s*0RHCZD zRblOv7G6Og^IAa`GgoI<=saEUrRB(QFggr&-Lu~IJLP2IdW2oV=1KU?^s`i&a zRIm_0cxiA1$!zMWmS00gs$SqU?f`)fHtCv{?B_sY5ZMXvtp9xD|F}SSeyC~PTc78# zVU$HvrDCsKY~}~VL6r0@KA3?x|sC{E9O zo^EB74fIpMI)(YT?WB)VqjH%YPae=A$L9G>EuIReQC6-ifFZ=0i@O9rIickFzU=ON zWXoH&jAr?1z49uxAMqLV6{UeB`kyZ|#Kj@*R?>XrmQfiN2*$k~B{D1!-m{a4a! zx|wV;r{N0?LIv}Wj=opU5u<+WPi0p^n)2On2P2sjKGCu?J&|+R%o4uznjo30b4Q49 zq+V@T?2#~iB|K)`g2{~!Zzl7WuGzq#3n0(d=QGdY+L&LS@5CGoa9L-skw zj_BGd#D=s>n;97cH_&?yK zAuJg7Jr?egz)RP6cu;LTkZs<;s2crlmDUHfi1S_w0lYv-0p-ZgE?CF28rqJV*yg zRR2z-5?%WVD&jRPfQ0kgT%<5#Xh7K{INxQuX-=Nyx=d-uxxj^e8e*%UockPy_?Rnq ze23O^cn8@C_`Ub>pRU25Nnc<$^8PCv2#3%^&#?_y(%qc*tQliLxNPWW2{O40?{LAk zsCvtBn(mQ&dpA`;gZp>F6wQHn-FaNH(8ce|1K$qABoh0DMjRG@N|)h5XeC3zn7M!1)jb#%Q(R3{{8&|DAXI`qjXf4-lG{vWDRnI z89(Lrd65nQsNKIe<^Er1eM~O~q&f=o|M~}?hR`m9Rcu%K(`5Dm?oGsrek5O)#4}$P z{G1ncYCH|$Qa|87{5r+Gz(Te^z!kH-`*UiD{Q7VkTGo|fkDbw5CE*pqA8Z*dRxfEb zR1=R3*Yl#rd??v_LG@^1r~ZHbkSmhP&zFRC68N8R@}k_|mgdtdfg%Q&5|OhaBlv}X zqg)k5gLiua0NIclh;LtT(P?Z!*9mNenyknKL5K%p@V7DePuBwePIL*h&cMZfD13bZ z8*|z40u`2jx$DS}eM0|>zl0o#%K!9a{y+ZAi$KumUJ(}l`oH?EFK+#8QUwh!aPw&B z{yrE*+G4@Y18YA!z!1pUjyU~iB>vC$iQ8uOVcbWz^q&tgykNOem)Tw0g zrafR?dVz#j{e5sEM|{@Yc^b(AbS0ZQ^)WqMD94Pe{K=hv{+JK{{b2uxtNC&lFm+R%O^<#JZ{+W8`Rh&rGYUv0 z!Cyc0l|Lrrb-l3t_3XioXmkR%;7=ChA2Y>oqZ&Zf0FdvW?oyzPV|@ysP5#6vAK=59{n z5O}4*t$b|;*su~l0iP3-n`IO;1jWG1nIC=eOQ-keV)n=U0p4&W!n0GVD&RZfb-V~D zf1di|$UU`qL@*POmh*23I202{{?ZQvO z<$MKHxB3#4K(ZxaN$X^N{lkO;deFCXWx`|Br<@G-kk(Lks&r7<)Lva#o zGGzJ!$P7{m0o_x4)rJGMl`VeJ-2{`Y4L`F$W*fOJuIUdq#e%>a;WwZ&v>D0@O92a# z0>BMrihd?lE;SH9lEs`K>t*W+uQ`&jY1~U;S9#fz383`{WSl|WlgFRNty!m6p*~}y zj>*}aYlj ze{G5XGtgT+`kopAqY`qU-}c7r0ZCCWfnNaB#4#c`eWADs^>RqD3po{39I%0av_~#> zltdQB=f%*uTm@#fR@H>GUnlO^*KWuJRlqOWIJNiG}x@1>hvtS*rnVC?=l9Nx?=1E4(rb_P~RF~TyrPhXVw^JINCv+ zWHIcO1?vxw#vqL2SP$w~!gUS*vMKvx9D{W*IQBUR z7(&j2H0;?8mV-qg6+{`yD4}0_YEi~FlsVwByYK^Gu*GOa?l|9=q{Ewjxm)7~_o6xv z7v2`5)vh`N84amkqqdA%tBw%Cq3gX``{+teJ8PIb(KugXy&?|0Abrhz z(`&(+?lZS45AU@w^l_1IXVjeBd^CT$I!4n&->oZ?)}fL*FXBkFh3v{0ABX$!r;jaz zr0KeZ`MRH_)6&5+LKFw0kVw$}NUqJGLxRHW_2|K({ErhjGC|kdFdyL5yh84(%s8&F zhonHxf@32R1wbBZrp`Pu$Loz3j4w0&_qx!s+% z`?*Q@T;lWD$hrNQ-4pVFs0v6KVi=wrenzr}@9%N8iktrfpmb_)qmrZ60>KlVx$=j8P-G|fL z^syPb6qe1n@;WaH3LH}J{V4B?A0W6B?OTiNs{DO@1}kYg2t)v2&@^Ovp=@zWje71_ zFn?>v);K?_LejTpJJhTGI7HiUC7HS!pEV<AWS33zZq!|i- z(1-Vw&kCaioY$OS+eBjpmL7~sFlyA?0l9G@dqQ+;?yJKoS`gz#jmh;Vf3Ru?(B!d^ zVgbR9s4zwlpkxn>Qz>t3J9HEAWp=~fSi2t2=%{3yp#w1#Z67zvkph#$AsOfA1fBl1 z>of^~tY~6jjHFgPOpLQZw4gGb(r8fe9Fvus$sz;1$d8b`WTlrzQu>!IVutOFrFg7? zs(CswK%V@%5RR^NVfzr{U&iP0cQ#d#99jJLO+a9`<4n;1J+1Er#Ib3uerCSl!&klO+lz$u|Kp z=hGY_g05!7!LCtn$hPt;5VS=U*ioa8h>a~;daRev=uThL6eHD9ulMch=;vUXKfba{ z_2$eY!FR@;HDZ)DgZ$m)Kt-y}w>7TQcx1G`gMBA2kicq_Gk0_=N_dbC8VvM&a&TXt z0cI)I?Wy}Fe8P;>W=#RI)(7ih-v6@KDxVEAE<2O^wfq8G>dyX6#Svk05ftVzr;rYn zug~j3dqAljtb2o_H8?*`z&5eJgF>go5gl;{k`2Sh|Lq#Ms03{IA2ELG5M%i=MyaFv!Uxsu0o_pcS( z{UGS@mNh&&Q&`xWZUcaJ#+(Uv5_5iGU@<6#p|K249#*qn=&RgBvAilu2X!I-b zQ9W_)CNfCr(QzYO-(pi*#dLW7jBcwshP&XtL_5Wsah&{#Z@XT%GEQR+Qtt}0IrTAhUHeOffny;RV6CYN!M4y0pX$q2TZohE5~6; za3{0<%JUieJSFr?u!Z44b)SkBsIo>$mcb@w{N{C&CtVXrE4!Dm9qZmH==)z5f-G@> zFZcJOw_h9m00TYEJGQ_IZ3DDStv3DZ8xi&d&~Wu+fnxHYQ~F0_2@dIqV}v(_eUF=_XuHLk#vi^9YJ^5cjO z{#UNYkB$Z_x-67Xx4wf(2T69}bv@1YDM}Ogg7XV!93D#PBBo_C0ZAI;~E)kKhR&*t|&{X}ka> zJ|wJvq&siN{aWf*tr{l?8_f z`|T1XMQj2Dva6B4b-*rUdPmOn^CO~I#Q$oQme-frix zoI`(3OAg^(b2z{Jbq>c?v(!{x;`3e>>NMn>K`Lh0d^8r>u8}FHOw;jh-HSEIf0Dbe zflQkPeNOuP3&9e=b}(2wzNbIcAA5drVbAZpd;gNvs~ovUGx$Aa@b}92A7AHT%TLq% z)nuLhXlhJL46>0!5N}L3HRS(X{KMg0jtH=^&&UxYrJ#QW(U_n8VekJ*w`LVT!^i07 zSiF|Yt+^l)g0!E|-n()GGtMWJ0Pz$BFs>OgXDIm3#!9aqbr*sL2Nmf_T#V+=Pd=rD z$m0y1WTEuTU>Yk9rI26Bi+p|%nwvi%60Ci?-BR+SjB>H2XSBqjwDlP!w(TA+RNR6t z$t~qE3W^Z_GjS2+bSvJQdu6!#KzK9Z81H1dpTiESu(gaHXOrYcm_`XqI_XaQF)W}O;t0$f~NFdr}>9X@|A z5+KjY!M> z2sYA=Ps(SCj)+OhalgQ`Obn`p9G*z^fdqinjf0*r=F^@>%OX{*(CzyKim*40!s}nY z2LI!Cc@YTsb*n4QF+VmH=2J`>-MIsv#!hz8Fo&YV`Qbsw4&Lpfo8b>Rlp2* zcCa-M4#%}QNnrn4!YLkdG5a zOJB#*{wQMh=xAYA%6gySJ^-M@^k?7Gm8+DE*9Nn~aOLHDejo4|xR~c4f>b?GtT*R? z#L_)yusm7eX~gb`k@rGROg>5}VmKkf^5{O^G@C~GG~5L*PFmt)WNJF`@B-Cdmc=bG z>g>J@(a&ooV8yqYcJ@*)uwbpM!bt&VfR}JjJq8e#8r^D$Y)<_B%<}r}K6u}k@}_dZ z6^p*5E&-?TUJz9m%OaX14@yCx79g>(#-$ahGdFR-nu+jlM>3|P!G1*M-uL-Hk*`nS z&ZYuw-Dwy-3OVpBkoD#2DQgzPWzn)L@Z`x80syQ1ENk}kODfuBp^Rgua1w3FI3y6^ z_%y0oTSr8=8Zh)9hd;*03=tSoIo%$?b1_1FJ z=uLxex1_}cHs*YIW;=u z0hOR2n*omB0~QHvFe*@&P+Gluj}(!Q*Rm)9tcmlBgHh~`kx@te&3L7f6C>&j)Q?UC zN2#LE|78j&9AQ;FYAv9~MBLcTlJia<{6FozXH=70*Y`_DMZ^k9RZ-a}MX6FFqDT>< zfb^z-^d`N8fT*ZQZ%T_&MS2OnDN2=I0t85;1&E=OgaFA|?B{)-d*Aoj`x$4P4`-Zl z#u}ojNE<)z9>j(;3n$ zGts^ZTw8i9tCRKitU}Mw`cj+EM`qNf9XTy_`@q`nJ=Cl48EuHK`vjG?ro{V@b_!Q= zq2kJdKA??s#fw8Ak4v9~3pI;-FU#fxb&*BUf6TUtkKQKA0*95HE`yJtUifnWfpTDv zqC>ytObZb)bpw}x(iB)fG$g&ecJTu>ui~!wRh&eqCtI@ZF zgw0v#LF}JGa07PI8wY~&%w?^iGOg;wCiuXCe@r2$zt&J8HQ^$C_yC(+vnODVXI)=z zMF5~T&d+zOpFn!9sPX50lhfrVJuR~4Gu!u`a`p$BU){-@>mP1qM@BQJ+;opl!6wI!$?dMcn9~455DGRRg8u zn%v(ms$ajq4q7*Tey@#L#ZRI01Ubf{gVwO#Z+s+p?Npwz{a`u!8SzI+PsK25zzon` zAczQ*U+tkJ=O=HJL7_W9y4yU?f^g2A%v2e$8|@;9GJ&pn@h|?Y{AM>&N%s6Z+w>w(Fms+DPn^S; z0<p9AU|#zy?zbbuijXNFQsjet`3qu zw_oOJ5dVjmI;NU4^``?8$YSpSpi?~!eBnHr0y~JHCsr5GyKZVCk?CwbW=)BiiPjfV zW1fEPs$#7DW1k0Ent4?kKUg)(WlXUu1kEJ+1s2vi=rG0Y?bP>rwVIC{&}9(^7J+BP zOww}2raLZbD?y&gp+2Ky4hZAIJfMK4n@9BklEZ8iSr=Ku*X{(ITST)HKiiJJkl#A1 zPLTJ~Td@2vsdj(CY7Pm+El~Vu|kOqo;{S?n+7YP?lLKL?7 zZ&L@{nxJ+iu-=G>*Trs6Tzg1;M;xMf$|NQZL6S(DWc>+)-27VT~6j_G!6hxM?JB>!~4whHWI%KU=MrB^)PIR z36>)tDcB`xeC2>=g51s(Cm}=5)v=pgvuQ^I?=QIU8hvMlkYi28eXyIKg@w*fCb=kd z4NzaFw7>6YbE3o+%;8itQ8J~0(mdS0OlZnkT-ey*Aa>XD8Ks(9LnIq7{FaA9A zga`FA?>I2DqIR1O;@iJ^zJXJ^`~jx~^$uWrvgSqtj}1Og{NquSEg7Am`3=T$Vr6&l zRF~J8M_9w6hsi#E%mW#EzkULXY770Nu#KndYa9Clo%v3d7Dl|l1;T~&4i5pxj;_{k z)X0|b7vVN=Tv=D++4g0&Ad$K!trpuxhk~5jBD~}r56(GGKfZ}(QeDjJu95cTH3Pku zAy4aEp$Q3~RNyZ?oBuoSdy3KDip%BZ$3M4!U4Z2CJm+2P+WOhCr!GyG^|{@~H}8f| zvmkD(ZSIQG4quuzt2NFLw0xG)u;Vb9CYvwpUg+DQD(@$gbl|h|{EPjY!OEU%uhD{* zR23a_$_7iMI-&wClpy$E0LsU>sr=<#G;i-B5L3$Nt#cfa_6Mf7N%G<%O!~mKyN=^* z77q?42%-qaP)x2jNK>tty)_09rtxaee&8(@Jb3oV9{2`a@N^Pdmh($1hJN3~d{!le z0_FA`FxeFRx_-3=K5W?L0F1(!r}s1~0A(QMbsHdbeKsv2) zg_;7PCGXylB55Ui5eRy+d4YS`$;zD$|EWJoZ+~;Nyuy+hbi%v<?tvV@-DN!vJjQ+Rz@BSz z;BvSAN4Wx@3PqE$)_Bibt6NQ({tb_h@ExLE1i3uWV}J5zfi7|)O+M2+d?jVJf#bkL zj-f$3CPGi>Wt4DRXR%TwuY{VX*$J|SH2}mtc8Q(2Y`?t{f0#lbvd=PWOmcCg*B7Hr zSvPjPw%C>@+%849O?K*r~_4|bh_aqG9c>rD=M905FkJ9Q7zjPVu>&8x44 z^)vO2ryp>pPAymLbjVG=ADz`FD=;hDjD7T|IFR^3{3?79mjE}$TSB+_pX~xEah5sQ zJ<~cg322ynpcwtl0`sx&_o}%6mpK{40qiiq)%7OdJG-?;rhOv`Hw87@tNIIpv8p)b zVLP&o4xd52ir!V@Tt!@3`zZ*eeF?Bo;h>LMWb)dhq8~h-9I2HdAW1g|_r&!;qs%A$ zXvalEX~ov*Gtt_SE%ySXekDcibU;zw zh7|nMw@Uk2`f~3j4fEY-V3>Gu0|31nDy^oJr_SDl=#u=%ugduHx*Kbx0CJa*}Xv|+uU`8j-pc3@cAo^jOw4ltv^vbT)Lzl*#(EP9V|$4PPICI~~k7nMUM zuFhIFpPXADfu1FtLG+)Lx4#=Q;JVQl9pH4Z$%5RItn2uzKS3q=Be5jP_&ruT1GV9+i12OJl8BRo%zV6LDIsOq_(PWwUZx4Xtss&Vz(i}#|7 z8~b?$rO$tX$S<G6mfaG9Dl*d2}KS5_Q zGEThk1=VnW6E=W4IWHDA`qn(LOh+U>-i>^!M>+q8`;C_4bI56r83{RGf)=O2sEsvF zeZfFx7>RLD+A%uXFTY}5h=!*uzn8ugC}hW1Mflx0J(|JGmv)xNi3c=gT$y?kkS+Xl zh!GYF30O1&m^CesAbR#<@6%L!esCkp`m<)Hbj9C!3M)U-`<5(zo~nB$^Sn3hkbYFH z8i;_^k85yfL=WG15232oEB&BtH))#%g-tv59o)xnG{14*AS}#()6dVCsYBw^!bSXEhbIU#DjTpOTSiD%{ zznPm`dgd?fA^%$v2E{*1Oc(JWKhTd|_xuc^7G4-4$*lX;t^1-z&4~G|$KN3#4Y!vw zMqON%`ah{|wQ@j8uag&2-Ry^QwQZ)quoL>b+Yu+%wr)3585cn_yLKEv7{&T)c_y`* zl*=dqFsh_bk48e*)2}}-i*y_?on6Z4(v;S?fo3+~7BkSz1S z;tGK1_i>rjLOKn9GDFNg0Yu^Z?IeUve$@IlGj(AE?Qje6RloF>imh_(XQP1`DVJ~e zd)G^PaVo#{QWRh(9u=8Ig6@Q#eb7IYnbr)6fFm)#^Edy9mRKF^YKZpp+c$vNwfMY=D$q~L8AIZ0<*jTmU(Kk3cQ48KYHo#t&M<*I5>l>Ry0 z(~xhh^`ZznH1^iqM4cC|&qfUw%Jq(s_{Z1yhny}Gu|?@ha!AAC90Qkp5bcQkLPq&> z8C@rUk{@ZefjD_@pOIfPGq*uU))hlT!(2d41W1RxJLLv{Qc3=+A@N^Duy_u#=ZoZn zZp2*ni!V(ptFkECqM+AQJFQKvz|!%s|At#igS`?WYqdkz3$#|h^`l;CfJF)$wi&P9xqq$OaUM@;bVGTV3n9CGpvWo1*YKRY?{#UizRacue# z*W>6N82MNDUW&`a*zy7_2%`~ISE5%T*2m07FUT7G_`^XDY8Pnz6W7NgfoFi588T76 z&g=g1PUj9_p#52;wXH5eSC}PG_xIYRRHC^ssBEd+J#-}!I(90hx-IOkVupl-b2~qa zdf>unwZL69wLwEm*j<3F5S^;^41fAFP2(6}{pQ(M?Tu`Q_JA?u0O+t^JQ&G1Kn8h$ zDmIsXS@ahu$-feFHm6KgIwsH0C@W>Huzwv39uRi`g#ia;W&!N!E%_HqZ{Xg4=(cZr zcTNP4>^iWAb#;Zw!Gkq%_HThJ_4n~K7I08hzcve7lo~0}L!i47uBzHK^m@vFXk$-t zH#fb;qvIXs@x1SaUaiFZ0Tj)lXK-7jtdS$*Nhrs-d9J?k##lKbQ_MUMpk0y7R3uKM z^cxGPwq6kYKwsbqLj7yJLCnb1|495dPI9Ezo%Wv;k(VZ-O3U*cLQ{Uku~Us zxAD>;pv3)$HCFmI89@Fcq6nJ{b-)Rr955M6uZIq+yqD!X8x)=Kskhhsb9}`$zA=v% zxJZ=VC$qc!XrwAvKz741>mz%QRl|Q+s!Yu9Y~pMlJ0v=W3hd1IE)V)LiH-*uRhVCg z0UBc-e^{Gt7NYEWu--4`!&!FX6kzW+TaqF>U(!s?WM<=h0HDZvX*&1L z0O29PR4$Mx0&Lf`^~R1oSN`u7gMS@zQ}r%(9i=q~(eBCT>#XM?!R=QdX5Xj_ipIzKgnt{95KmsmjhSTk;Db7;>wfv9ep&H1? z^^}^D+dy)j=_5r;OykUOplj+|1~nOOgzXqJ`|VU^c%>qvbH$)T>Xp1cdQtRi0_atsiMX_V!ScVTc3-EtKl{Psgy{v(nZ_ zn-{sv!XvdtdX8T>LPWf|0@4Sd1kRAuc%)(H3@X%9wrMzh)vw>YSiz6@MeGri1w`i2 zT_uZClzn(0iT?7VbV6Xz(L2nik9Vpu(Z9JU$I5)?S$x=B;rWx7g-&#ym%~lYjcME8 zdM=fJevUPvcO872v5EV-tE|!#K+-(^701fQ+O;57MTtWyJtDrKA z?h$TxRjGM(p){MXOz2T46$H86@`-alepPTs$lY2|F+9W4>6zKCi>!{f#so>_u- zru8xpe%3Tg*!x z%)ZHwj2c&^9Jp_FwbjsLe2-Zzx_4r@N%>yg);pp%MCvFCHj0WSN;OQUl9T7;(n|0@ z9|acD#wlUFsH;03c*2Ap&y1K{BYfQ2vTD;453BP^6`lPA?xlpQmset4@kExg;NBY1f}AmV>-)80RhCu+uDj^ z%Vx0=r_n0fX0{AzYBBI8y)yqLh9HJLdoFrqER=~%hrL1RUW(GgjEhHFKP|4T=&>ky zV9x2R{G{5cbXOM$jAV+6`TumD)aD=f_wy4~D+k7(P0cV_sLq+sP|!MfE1l#=9BMurqLD%huBbVWq&{DI7_e@;zW= z+Sw*FH)^E6+;w(Tx7Gl*v^VX}mgbGX6)RaO<#3IAk&IF2QPT>d@|`OQ^S8Y)1x+LU z6h<}e3Xi&;!=5OUlI2u((c{o*91XuWI6XwEqZS3aTlF;E!RHSQB^!S(WaVOcm+`bw ze)apZE?Y)C}}u{IaOd3b>1S-aW8Fz*s!z- z?4|GHN8Cm&s(AM&+Lo1NU56e`I}dk#J3+Gg-Vo_As^^K~E6rH(EK!*)%Ik~eamOp8 zJT0zG2vF7=T9n}pR`J`*(k?;;#0+E^MG>E;Q(0nZD2pA9C~|~qr&NC>8Y6IDPc0Zh zEujH)x7+!5mf@Pa7Galit=-N^J$A+3`t}63od@PID&y5I@ZvBHoKik(%c@t|-0t7B z{ac3+jcA zwla@Y>)AY{mHM7|Fk?|jf^Q+_)O*9FjaxS&O*K}`{NoUL@1SERRRXMT;Q)CeSIN+V zW9^!Lq4VlIh2Oi`Cw<>SGok2`>B%?@PB&{+Z-tCyTUh=oLs;t5@Ll4B(S{jk%Y@v< z0$=mB_)z3^0=vwWwcu)tUo8kr)Oyyt+qZCCN_IbWa7ucZ*#wrK6GMpT6%}`wzyRae z1d6e1g_jasYqNX!L$mO-zuV4e0HrBsb*BRLyCN)c<*PBwGOeEaaT~?oV8!~?J1_u3 z=rOLx_;Wz1``T_p8C2)A+GmE?vc*0Xf-sE3mt>47sLW$knWDun4q8}0EsXhk3O7MN zI*W?u(8No~Oy~vB-SiKn^&NZb=(hE4J`}-7nO3$LwA-L|Ky8-?jc`s|5iU?npVP40 zRj5+BwuRVMN@I1BuZ4iD>!iB>k4a<7k|6sS4|3&VBP+DVu8}3Wnxw@Lr1%FDnTb3g z#t_tkIJ8FJ(kf*&DtT->*^k8Kvp@fck(q!;a38a`g#Q}#nBX`jAT>OaK|NX0e2KO1 z6aDk)V%lhvt7_m?vh{+zT3~R==}-2lv-TrfIgC0fCt zmC3iT7e}1Jsjp`3e%iDjE9wg)dh<-^tq2{C!;yake2s>NT>!5|-4Q52qbhz(HNCnb z6J7xch4~PLuHWmzcPzLQF_d27bCR(@#5BY&kWz!RV|9FTB*f;m3Y+ zt8Bt3UC=gAbF}~_n>LU!U96NUxF|Q+PU!vh>S@4(I|9ioT5Cq>;F0|T<=ZH|u;-+4 zKAt`9e%vU5R@FGSUs^^XGk7w&tyarebX!SkWf#PZ9UjG z@u6W@Ng~Nr&PHo%(d9<3AAy;bT)61*w zbqaQWv5>j@SJ9kY?+pdw#X7S*6?bf|oRhGsQG%u#5@HN3#O%?VS|OI@Hp0Tx0A^w1 zsxH{j?wNq1%9krEq+!B>n>_DX2+-*9OQhHQM#C1!YHnk4A&fnL8x!!L0QYfSc(t{; zODLks2+H9Kulf}eIYRPOYRTWf;!@w)ln`SEd2Ennp?B|;LI@!kgC`-0Teoro`_19} z%P=G+ALFj@;3JHEb(?NAHPWQ3a=w$bbUV-+Q2cdE984Y7T?G_Aeu3>Ln6?_E7twyz z7>6PxDH@juV27Soj?J;&-ba%9-}K7Vqrcjb=!jLPP&p3uE2Ah9BkU(-I$P_ML&@E| zV4o0`_T|3YO6vK)DE-kmG>8fL75g)uLGSmIh6W@JjY?41!^HfX1g98`ON%|4RVlw^ z|J)}8`OBsbTjz$CjPRP{4gc!C2f~I;GfK>4?Fp}VpvO%q;QalH^yR=5y#8-fkd7{B z=6f~mUR#faXrg1IDEpIXq@>%F)%~SGjWbst#eV<(T|w+g!KWs%8xM1ynveU;P{kJ( zlOx8aT`{9KI}x%w_x;STwkv5_&=h@tmj`+L*2O+4{l!GCyAR##ebGYB@ib)V-4p2d zjoDriYQdBT)MxuE`WISc6YI0*_M1GG?kN;lkj#OxVPicrnF|^uoY?iK%HJ~J(=DsL z{2I?*>Oy7kc9-;?2TSlv%}gzmr42ih)@mMWeHHKSl@V0cV9PjPiCwT0v~?ydnc5u? zKx|;4fHl*B`?XU{$>X}fQf&@-C#b{c)!t7kmBg(fN$x=>OO8v+utWueB@8le7t2pK zBDZy`fw;XpHI?ydI{<4@%@b6rzsuc^|El9#NOe#OpI(VVG8PE$W5eE9WV3Q^opR;d zJ({Q~jn`=Y6>p1QcdB}!gOq2#1dMOz&v@DagIw(|WiO5?hR`ACAQN{(ILN2ymFeh0 zpx@1RI+Nf>Ebx%`8S{{tq071jK78X9cG2nH6nsf@7XU6&Nj(|@y3nH8tK#%EU9-1mL@#XGiB$Q2JG>?U zSB$K5o-k34RuH;JN=q;qSvImvt{-o>I=WB;?&!t^4NcB#wvC2toJmuu933djASb(N zE;0S#(N$p6yb7N$r19XfJcDCr0^k;q~4~LP$NE>y;SIQ5|Ymd?J�DW zVuk(}V@$Dl+yr4wSt%q_i<;<{6_=hW8jgq!N*>NL$YS1cm&$z?6A?ok(pCr?Z?yE#R3ybDHiA7-`bmfrf> zLfMRUZ>DdWD0^ITI;i&J%Sk9C@li$}t-+={rDybeiTS>^f}nZ(%TriL{QkLoqvG

_?N96S>n-=*{VMLxTe8{FD4;xtl z<7G+m_>LWru@H#2(3efFaJzftOd@}JfYwB%gA2SXQCPgp$yce8zKQ?$ApYjjR7J=L z`WGzVhG(N|_vj0^-?!!o)p(&(6FzwHB6MXUP*plCX%xd9G=_SGOWYy>824zH<92^E zzTeq*XWYB2mDB;Du1D8{%g0MOjf#x4a2`?%frbbWF1E1ly`dAJqr+Y}4WD2237z%l zIX2FGV=BV!lOpsK~f`x5*lZ$zHGZ;73>03Y*>y z{q{+n*0r#*@EmA0DLZacz*4EgJZ$%bKvdjN_$kKOW2^G6__+e@Yw>+4zUf*uB2x<6 z7etqSjt|#jewiPZc(QgD9X>rp zVLo>3P6`Vd=`@lAM3SkIpC2T1)CZniU?m4&oi@Jp=$1WIvWuFV_gGsSU}MKqsEJ=t zu@m0Yadq36q_>Zp#wIBBIzpCg*kFecOq~-PEV0j}949Y*1fR`djfb_vVD_7Q-JG}k zA55&+m;_sdTB3bUU>T`*LO8(8k8w8kP}5ntiEzBmBh1}qsRSQlvMeN8*k7jtuPm3I z-GVn5=FwK)CHc*j$!bjQW6Cxg2JPb75*!#(LaGg3XEj|`tM=TbE)h_=A0Wuuu&I8z z^qr=v{U%S0mqLJLx+(5RlQztEr>~b9WVh?R|BWNGi8{4#zZT(ok5;@tyzqvp@pEyo z<|ps_=#aXR>DX$X$|SJ)rL?)!saFt{+>EbLgO}u&wo{Pt#~Q<5z^=1R=b(i8&s&yk zmaV(T@parMyxZUX)V*Ce;VEPFV`XTtes%XG56`v3hY!;SRKXoXMUTJx_XUsc_Q^;( zjFv9jnjTO1ZiVNs6LQDla4w!kE}m$!*z!ks_03~Sw%gP@Z)h8c70|vzUj3(G-)qnq9(_Of5Ft#t$naPfBGnU!AEjM(tZH)6DG!|Db$=qUzO25!v z{LDakg`Hmco63K_b|;IKTsPS>Gu~}W4i~iTBA=sG+1l~@#2#Hs6wA+4p?+z!o1cA| zYO|Ln9p_HK>9;df3%1<5d1&qMT9!EzIRpYeQ#!iym*87;0UPhs!XgJ>8ICN3S_Ep_mM!%XBg35K8- zVgEUpw?m@U&$omppTG+8{>MIk{A39;*-*zao`Z5Mj#Jy@-2U#!_tfflwI8+&jfvx5 zTHZ&w$ajYl?zx@|TfF!`Tmu(no`iaPIv%pW1ij*!`}1Too-ArzoY5>ST`+R&U1ywJ zM4?&DO45zjAddGt_jk{}{wxG>MVs4yZ(T~_>DUX?wzQk>YUQ>)3zNhe#f=U@U-q@; z#x1*AA8PJo4SANYI!CSVcXRNsT@0VVd(z-)D-N&{#x4JM`TU+Af*-m$wC z$=!iU6fIU9tx`#W6g#fBpfR{q&>Sg8D!QL~Q}5MLvihjl_@!iJnB#e4F|)#Z1q zgh}`Z=D8I=@A;q7A7o*%TZHwdO5X*-6tW~p2KGyIH&;sEvf8U+%d^efe!ut~ucBJi zDnyhg$qh+>N%(vT@+SsZHHe+4eDc-AzZpemHyt%tZwfJ%@ZAyBVoi^NCU~?8bv?jQ z!+m(mYJrjW1<%}Gws-3%|A#@gEa^qZZH}kK$wHOKn?v8|x17TxcK zz^UXj4ineaBy77xpo;6+Q=~WVpz3W$&*coDwdeNUTnqKc(Ml>KEC%)PRLA`MP~Kr3 zt(4Rt0!_-Z8IJJ?m7MJ3uRXsy>~aYz@2Ly|^3G(T=AL|Xzc*PtW3Q`iiQH+Or%80~ z>&S{$zIsmbX#(%Kr~1-K+uyfd^qMaw8qP;#ak=c}^ff0DMHMEjJLZ1w22pYI!ggqi zo058r*VUbmt;FrXG~C5xrD-v~y6$dq&eB>FDHmG=Z~qO8+aVm{e>?dsj;%?z6oZAI z`Iny1&(e>Sj*L?qgKXkjqj?pbFJc9{v!WFPv_c@B8)ls`%3(G>0Rm03cZe>L@xKJ3 zDkXP@@}S~?l2zd^mO<9-N)mQMcYYAeO9;$*9wgzKa&#Xn*h$ehz;lW2rKBnPjV|o_ z{XCs&s7gE$*4`01=69}tSCwsVC`U_3YoV~zqn(%@2Ly-l{muDKyWNVX>nsk_H936h z{lT$@5%STSaiT?%kLPSO5MqrzO2OaTPc~ossw^6F&CXRL{z_3rGh)1@(at| z@E6#K+f}1C2!#k~Cz@meo>4J*?54fj zV#u%1?bYq0R6r^+1xLFQIInG5*mXrW#^5ceAaxm3z36rNM+{w}})oHx{RH zcrAic?8@O?opF=>6(OdESO2sOHt=Fe1ZtDBWi`4tpf6sbB<-f3nu&~)6FqgeQMuH8 ze*n#}2lmYIbE|x4uQ-zty!wddNRHWuBXKe=CaD$Z`bH7*v14nN;yZ1k_%VQIoTk)G zxj6Y6LtBaSn<(}AB))6|j}2AuiFPfDo;W!306 z5LY$2m;DeiHnDn6!X|-_hiLM7-~K^J2|Z=(*C}Tg3gF(Wmt|gd=G!+JaYReV%G){8 z2P3j#Mibu`lhHMc%F8uj!elr z_MiTQZ=|Zxrs)M1GA>$ZJb*IMog|$KVycN_N0^+9n#L$2UxEs0X|Mn%lz*6L z9BbZh-qSa-PLxaih)4iygoM_cCpmK<_VQ&S+eMkhJh}T84fBp9>v`bj3Mx8LDpud%gFy~_t2;>ns^S@<){?`7HD|f^q@~ZSanW|S+WW@yycIZ=a55Zvkl_&ih-~QuQh9Bz$MOC1@ zm!%sF>Vl$p93kANu>uqR_cP!t%=N3O()fw9(!jg4rEUwvrSUvm@R|}jNbd*PcF8`I z5|6N_p-5af?E1y)ZmY%nA}yHGCj~HuTY){?ZDS4c!Lx5&;^aJ^;z6E3v|#pk9?`4$ z6cJG_=e5EtncR^*pl8#%AzF1snO=Dfd;ISQOZL%>d*5d@ zbidr$sIe;8ZujHklCxt*ls*wud5=8;g=LS8~%u_h&O)R)MB6DxT5!Q>?TgI!i6l zM8f;q(Is?N^IS(pYZCk5<~!(Qgg2(Z#@F5mTS50-kkG2bZ!wF&w* zx{Q(}BYI-B0(@4iSvkDYR!aEq^zX2c1USbGOa7;TC!h=^THxEUu~RVLv2rT3DPz3p z36*=iap~5_WG~8>Z3FS?^SEfsvgzt%nzPn)ko@D^Ao<`|ypzFW0jPBUWCd%X$drpb zhR%uNeHO`M-t{gD3bMZ|Y#k^4y(0q&B^H$yVtGu9b%i}t7Z1)AX!_0Ws!yca6hA%A zK4UR~=nofD4S#fPM?l8N*X)YBs*nn{gt*9O8(8BV$|Spj)kk_NPfqtl-jPYdl44zt z{}AVdN~kg7XJQTCJ-2ZoSRp>yrD|Wkj%4$3_0c~?jx$I)%<9&y+a+SK9NpTk!7^>3 z`qJW8tEL7n$-l?T(J4EGbef%|0$g%r7b0?K?U(J}eJ5Vf(Y{iytSc-{l!a$&#E-_d zjn0)kDyo_T$+B;|$rgUbL}$78%P@f}|8yU>LulBgbEK^BsN^qa3J!Gm><6KSIbNL- zgS|Vn?WQ7+Dg(G9De(P2$IiiX_A&6i76-Yi)dcfO1JnT2WwQ14KP?LXx5H_MpgRoz zw4Q_Mee$2jNFessKP{(BLR(p5hxTnpp%pWbVa|*5vh3}N&mYwjA?}e;J{ocR?EK4I#0~uT4qedP?}-~s6QQbW(U9fmmXRZew+EnUw^v7?uJ1Ba#Mf4hF^ps z=&yft@cV|f(U?`@`{(SJM!xa9oTi!FKo_P*ef9RF8u(ev^Kjs9V@ WGAm=T9P(h`HSX%%DZXv>{Qm$M-mZ-R diff --git a/doc/wiki/gfx/motion_lifecycle_sequence.png b/doc/wiki/gfx/motion_lifecycle_sequence.png deleted file mode 100644 index d6d90eafa3ca6ed0d9a400480810ea6f9096a287..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 187370 zcmaI8$Ik4`vL$u|s0E>cegJ9y1FgY1pf^K$7QJ^fda_vbo|7KyS@i}QDY^f9btM66 z>~EJzx@0gjV#SJ;^}kz&^k4q-|N5W*@sEG}mygUl|M`CtCe zzoviu5C7@^*o0{7ud4l(|M&~#{{HkA0yX2h{e|*>A&BrR^KBUi@Da54W6@S^S^T{X zfe_@M5cW@q^dRUjltBpaf)NWF9@9AzlQBljOPkI8XkCoA<&Gn z;1k$DV1IwS2<(3YEzC6i%COATcKZtvag_WQN`U77s>+_O{e^Jg^RMkn@FtacH@=4y zOM3pR9l`D}`Y-xlG-%?QW$eLDA_aQzFAS#8f58Y0HvGq(iJ%wozi`mzrd7JM|BtJ^ zH(hRN{r3%Lo=x>r+$%mWSi4C5lc$TnZ}cdawFOrCW3zw1_IvPlPvzgOMR~M2=*ZhT z0mH2SwlnAp@)s%q^A~MeFKG|9xBq5gL$xF1R)s{SKPt9gdyyP}pJ7PBP5rr=W4iAt zKO%VfC;0ELuSvM{eS1$#2JlwUBO+QDJZRQ7$jo|!BSaz;)Uc3_&`_P}FNCGVnh6Nw z2_L7i9^x*(+}64$Qyg_R-JRnU*{#3(?VyV+;SbAM9wH&p3wRoAgx0YN-UoHX7yiV_ zxgPzXM8Rd}$7}2GLtPvU{XT9N$9o9&jM3!h1_Z&6xEpptZI`-Jh-2@aR&_P3GZsxP zX;h?5qdbUAqm@{!omj1m*s#T=bZZ38V7rC5bEOxFQb;9?JpJ8d zC7Pi4QD-KV3dyUCZ%SIQuSPy#9I~j5trt&B`D$TgG&fa+KeO6c5e`Nh%jcOUR5&pO zlVUvdn&CcZrAkZo{Ttuz;(@7mbUCjL`tvT9X6fx;P}b0(4t#^1X7IbdYgCW!4mn7q5Bh+1*|)jD@%muec8IL;9dy-o1h9pb zVb7MqSBUC#^qd^b^97Bez$QMnS3MU_XgcZ-uQcZBNmFYJ%qf4&Sz{)Ct}F5#N4o;N z0~md5;Z(U)f}M9Gg+2x>rek^(vQ~IrN1v!kn?l;Mv6IQ#*@#swbXZdChVCCh z=|=bGE62heq~Dtt>mw`fiSyp)Q%FseO4_4Gu_E7i^UbY>Bc1t&JB`hfAA&G9m975z%(8^*VIBVTfv3Vkmj_5=A z!)ai9*EKi*MxL*;St_hcs)RzD6ts{$=1m)!+a&kP8dj+^Et7f4&3@{)0q1NqH0MZh zc%OD5LosLyL0@Rv70)VB9{BlwM@WoGPQgdZ-46ros1=z5%R>VH`1^tkQPP*p$}#nn z%!m_q?Neoz+!Ki_vOY3CC#5*b*CYL#b25mbs4~W=`E|PNql;hMTP3*#ZjQ}^yN!Ms z>JDQP6CO(<6!-d)?glUJ9Mz5?VaRuONd>RX5k7VL^rFi7?rh$N^N^AJ?w3S?mmMP< z%UH;f368{6a%s18kFr%_)G{fAsNKP1MU>{0-w_%|KlC=L9PFEr&Zv?`lE-GUScx$N zO8|dFBx9i}W#J9D6fiejCMDzrJ!}4>01z*0V9uOoaLGK7^#f77@4LWHkVk(``J?i~kWlyapV%z)c9f-cL05YX6N*ox-ERZKAc zgj=u1#PQ^o;^VB94j&q|sds`NhGUS~@kL0Sx4Q?XwHig~hrRk>;qZhvvgWugoj&}f z(x2D8er8xV)?e#hZ%@Vh3*s$n{=S>1i12q(*iKKPCx<`L2{zayf|gWiyi>X9Vs(sJ z7q>%1`Eq(dpU_W3b!KLyuGUgwnltSXCVo7)5CmIxq}8zzlLPVM!k>B>DQ&vH>F#^B z^R6Rxb1bH0-)r%+57CK>&{Jnp{Edk)gQL5U5Q8djQEoXWm!wpDqKQH@(5;>>$KL2- z+n=3Yct`wHhZtosoY?wR^yU3LXMbBsI*G@sel?r6_s?ApD~K{!CeK|3?q&dwT|9L~ z-uqp;6zPyq??ch<`zW|OQK!08l)4K@ zxbbV|??XEWyry*Uoc^d>#ksL>)ajEl1cBgcl>m1?NdSGe`h_JjyE>N*cHrGMwP#>T z3r3(Na-SCiu)wJfvw2lU6~rSN8)rm=m^V-r<4H?>yj?6t@boJ2pg+aP7W*$<2g8|X zC^p9QQ^KlZ#S1$@p}bXR0;!mOW<&~K(+Zoz z+8j~jnpy!2ANT03|j?G3iGfa+y`-oioANKAm`s;_L%2(h1etUNbeQ= z1;?2Yh`4MpykJyhRe8q-5ZKr*l8Sjv+OMe6U<0>cj+&76@2TgA6uwYWe@ac0DvobF zOPceLblHqovl|xHKDF|soyd&1n>+|`~qyobj?os|IZW8V`{gi}T!zj{ctP9aD<545o zell@Q`*|-^qZ_f*_!Yso2G_eB$YvVo=K_=`!ld_YbdFIR2-a*@CjDge&ZcXeK2qvX zijVA@cqGD|`wD;VF9WOafQB=*2nH~s+KTnVGqyuy4sG=8Mfp1KYrK_C2NF7whO13P zD`xWyo9MHF^SgWiVM@ZWbhz`+!;Q}f8Z!mUs@0Hk_=jx~cpyIpecjU!^Oe+^Fi4iQ z(Vw61;(sAoqsn>SV%pDjZe&xBfp^E0ucq5qh06M>Il>V)+U%VqtBh>XfaR8DWF}jW zlljeObEU8t&`4xTeobZ zZ6iDv6rQN=fU_IN1s+)xcdHg_iPVj4IHy^Yh3=|y4#b8TeyvJt7qB{f*Tt3$)S@ok z>x{51qs*iN$sgF|-}Ar!Pcrx)sh(60<&yqDdIxgje@pkcv7g4_O|$=Gmj9kP_5?Sr z+KFIQO*2qc3Q1+T5lQms*ar%aTG-n+mLZ2|ASfOuCNEuKQ{l(K3+ z65~MEMcn&-ufu^`=L0GzO|^5uTH5H@2?*JH9 z0eiC`$4WL50`W*RAb=o{XE9z^Pgg9|-;a8wM|4$P?A%|81hL`;_wRG!w{q;O1AIbp zdian?vF;Jll^-AM5H=v)P~mq@ex1^Sqp8>};yrBr8uRe9*z!vqa4>s-0U>^_>>}Gr z!FJGdkpU=KES$tDULOikvJp?w_XmXtGJy0Jg+t{9@?w%*ADoU*<*=u2I8g;O!b@}@ zBsg#BA9T(S;0&O{q6z|rxW+H|BfX?j4>|)4%WI&9uSU5VdwntGv^sII^vK`?hCFhT zJVogdnGD2M`SebZRgrd4nMnZDi+6^-Q7F8xv&h#ecE1HoQPA7v@?$N7Ca$3vuFZyC z)&vLJ~QdU z<3Ict;rQ*4p%iIPs^#Deir`<7zA3swjEZ0mM}6-fPYVU(dAzpDJp~la>2bhR57d$_)ys#t5lF7QkfT6NHGqN)2 zHDXB)CadOY0_-D53+_l(e0ZV4gL>yswWIk&yz_a|Q81>(5W6jvCO2VdnUp9u+sg+5U3=Eu`4agr> z&{3w80p-q_Cj>=vzW2v`y?~}wO-dvG+miy~tU{34X9dRK%1R%a<6ToimE4;<#;;c& zai>JBWzi7H3QRl}b8kQYP+z}Mcup5YiuuHwxc}xzv?gS@G6i*)QZo?L5{c{BviBfP zEPf2QwMY8_v=~p2aG3e3B^QodWuaXN$xYD@(JN!h@9Ov9>W2FH>?0{u?AqF9`KG~X zvztR2SW0m1)aayVB}GqZzyU%PGJoo6zFw*~ghHV7K9hvsybgpZ;twf!d(;^m^D(U@ ztiHi!m5hBe6jyxA*DT?b-oCA)28g^MNucVbzObzo1jP&FU9{rG-7u2t?TXus44N7* zh-^T6rReFT8J+kw5xtJPq7YjnArmAmy+1N?-S1ANmhR5IvrlpUypEggLGx%I(J%+< z%tTWjLv|-fQzK7pdTk>+en`zQ>!YVH5Rq8!V62q09hsZl$o!CG=(~^Kao6Ij?{hPHMnOZ{3V3G6~N2< ztX~bhhp4P#PED?+{Z!#6GHUlxDAQBmFo4oIq=x;ytp;RtkaNBvqqm<)Q}U|=S%Eo? zn&9Q1vsjeCKiG4X0O1wLMZ7m3@3H!iuGcCt9gpp6=)L{OI@ml}&}7-L(*8#cm?(Pu zrZK+cJ@AS#I?7jH$l1M12zh3r@K(8r`Sxo+3|F70$RZG}969!`uCvcI74!I0a@ia@ z{=q!biX#!7eyacG3!Xj?EGw1-UXDD-9>u0gK+eTif_-O>h>T9A8khZCMm;FCDt*2` zF{${Dt>iipGZdagX)Ps00=LZ$%1MpCtIUUmdB?`kTQa_9cf4X{`(lxP_Oj{PvquVO zSQ0wQnF*m>^O^W$zy}Bn4-KMz{{m9}#k*YVbjhA^yFU{mNW>>DSg2TC77DGXnXH2#sjtaEf=xsk z8CyWJ3@}d`NVn?NVInS$;~=Mfd%Q$vH-;qw>GwZizMF8>exk96bqua?2yzQyb9A?a zJftuoay&Ag&o8A2z%mnZ*Z#&;m8J!dLcR~Y6@r`@on8@@sbVMKMV&Og{bJ%Lv!SE` zAJAGUt|yZ>4UJYAOoy22+;`SCDa$F@ffrGR(b2&t;dOMp?n;O?G6}SGg1z5ZP z;y03~Cx$I%&_H|um(Ta(_lg+}6emEF6wIA@Fd?u>a-zR%7gbk_A{pMI}o( zoNGJlA(aKrOS2HtvcEak3=Hd|5fftA+TN01S2$@2beNjQXoZUFIa^8Mh}!USY{0W!yNzQ2y@L8g+_C9OvrUpk-Xz0=~FMDr@mih(3B zc13v%zpezpj5yfTZo=A@5=4zYVPRM`*#9>SdT)Oae&W%4xOXOL{U!>6Gp0VoJ|1vX zK4e34F5>_!DL%UW?N%<`$PA&ka8KlS!p5TGq$n7rV)xZQI@Me;H^I4-RL%?0pd10O zGQif|z1Pw^?05IsTYTtlQ7HS;Tz9lB^sPs3X@5aI3*qkohFCyxzYuoK?;+O9-Y5Nf z5g&Aq0)NI&+VD-!CX;uF4ZqL!0B+&XBfgp2B4}~Y+Ks{vl>ZfWoMtJ7#p8^MgY25AH0Z+?wJz{_zcPmm%9p~Pyq-nihD^C+jXUa0fL!h1VD`4 z!mrmM`8TwK8#3eKOraIQ`2;`r;zTQ{(&ZrbuNwpf7GVJ&U#))zs}qY7zd4;!lZdM5 z;i{+Jp8kvwI9?H-*o7)Tf0#r_p3t!=Jq3S^+>hT`@1=uTOxP`x_=bJrl86jiK&zB+ zKku`LGhBgXzj454HETuhPw^Sa3NmqHs2yOC;1Hv()-v>v9@mHx9b>;Gwy= z^UKB9H}*u4Kbb*(J8nz?_U9zP3!B&0xaKLEm6(=EXB+jezwJmWEjcCt;obEqXQf){ zD);(ju^j+lUeAByaiQH$m1NQWjTmx0vW5EK~39GI&Oy##46 zz@^6_!#?~%0R@CACtCAdx;kd8-x(B%clOAGXeas*9D*s#-ZCh|O!@_U?fBax*F)g1 zQ`Pn^Yq;+-j~kYtu+XiyP?F5SNOpNxwTe3z@CPDbJ_{xa)>W8*i)0x!<2yuZh}{cS z6J2RxLFN|lX>Jqp6KtgdD=nye%Xhl*xC!&ioF^c8uH0vGb2mu6r%|GpO2`R`rCO3Z z(nqJa-tfdN81xz6>uq{i`z;5pH;APOPXVIvw;3O267`U=L?xKf>G*b)bvzPxq8-G) z(=Oa3A6S)DY3t*Vx65=7QtyQ(zGDPzFQgyI$RYYEkgCRiexDfNf%D;y0lMpk8^wPgB26&k+^52Swj9q=Ow!hf9LWo&;@@ zOQlW@cO)TaA|D43!s~;JW_6uZt8kz=EPRWub(&FeKdDoqrt;ldRfdMBvQ>2qV2=H% zTaRUkIvyxv8}e4~o^}hbO$2j=T`}jlVPd;qP|RMUMFGRjgy-W5s9)0n!-Cuo+;AMw zlWZ{@S+t~8ZCV;>>STt?ZtJ7@S}XyFF`(wZv0PzonhIHncZ1rJL?PkDMbBfN4`EWG zy9o_d;^ZKiHjNf%Q@su|FVq(zA^Q%e$Qxy8E~m#;TCKq8K<+brzi~&RqK_hL+uf7^ zG6z`S&4WWKd5HRAeVH%tXGa;m%ZJjye&%(6s|)U~Gv@P5rX|Mi)|Me5gsuw0W)dJ) zHmN)y0l3ZDNody}Y>(1-zG%v`q)?$bPIXiG;V3c|t8Jb$dS}ZgW&&{)PC_5T+f}^? z1Ba7J0#R15v6_I8L*1RD&=_*SrAF-#kbG=~V{qn9$^vyJBqswV`3oXTU}qn!|iJ5=sRoib$D5M4RBl z8$f8vA<4flrJyKx7r_Zy(-8eK0w@EbdHVIdU3Xphy~rEo$?l>Bf{2s{1v&=BADEbq zK0L~;hPL{Qvx7VU5HxRe2kbs)ccmpwS;?F?wt;iAP>tznhEhrK`-)u~bKc~Ummwz@ zPJn-O64msoJ zpM3LRZ01^ZhJT`P1uD(o0xAFTo!=k59r~oc@Jh|XWYThIhuG2y01tBTz_$GEWb<5t z8OW~5*{_=j@#87?w(U;pg?C_%i=Fs^cBOU|2>Bs42;oRYQTZo)ZV*{Tz7+dbV#i3x zE}17Av&;DhesPW8>zrZ2k7pSgj_5^w9$e84<*!F{LKvfS;kv!s>PvJfy>~2d2sq!3 zW&Tm&zaAH|o*V#c0UGmS?WY%g09^G7)&6@Gj(;y&m}iv&0TPreHv3Og%ac(D4hjq} z=s#*8)-rB@9tI}29KcuRpTr+dwB`eTpg zUiis0B7V?nfVneiK2(pK+Ejn;9M-8gt|`E-e&^^lX|+*%@D*nu!J5mblm#ACMYL~q z>}>amY`O8kPOm%Cqj~)@-f;F@_z(>r%UJ^qC644$LpV+IeR3s72;fGl9ZH9K80H1# zQYth0?SkYt;K%SJ*86QU-h>;YG*@4p9g4m;C@jWb=cLHKIa~J$mdN34O~=m)F{bL8bjuwcv(W4cy9) zSSf2AyrK#dko$>6BENpB>yXv~70;@_GD`q>D81eemGc8$(Sy91XE^DkBB>orR@R}- zAz|M!`A%KK%De39!MGQp4V%8NZ(3p>iYuZD{1$D?;G!fv&H+F@@U4pJ6UZ-5bP~~D z5FOAP2HVBL<8eRBK(&|UOI9K%!rPb+HsSX$1AT&4^BPV0Nk$uD-$MuP6N8?R7GNk? z6Lk7L%h!4{{@jDmLaK}hrv%?d5Db*O=N-9x2ARL8M0_o4-MsdlTp)*j2~)A}#7O`( z^^AOgRaoYf92Nqe%uF4fFw@%sjoA!d-i?uUf3M*)L`v*FaQ>S=l}uc z1G}}BMg8m+s8_C0VZ2t`Z3S+W(goGT7e2VF^zFkdUdMO9SZssZ0y;rxt*ag`tFWruL^0qBZpla?Hg4Mnk=pTzmRQ1DE%G)3 zQE*VA-ib;hH?%a#cU;^+&H16<46pA2%(ycka{$VWu(*S!>lE)$dn-et2o2-H1KbEk zR`-*w3U+X%T{Fx^!73tzXm9$x{59AlI|WQ(VIcLxdMX2P_ZJ1<-}%$cxsy)naCipP z10O(ii7=Bquam@RRbB!2T~NL)g;8k`V<-&sRi!U`paYr+l0Hba4{(vJZ6CnK&Y_tC zt;OrqAAiih-;Nj{@MVa@uORDD>4v)hSrBB_EpGs1>31`5InSH?*6&$!*+UIhe}w#2sCA+aXIz;SA~ItM_GX;Eqf18JGu zPNcWS)TnF<6-D}8CXIi}gy1pG`EUoH?FT@^dST_b&fuHj>Rpv;3roGiC~qkr!}0Q3MsGWZX`GC<&Fx(J-0F;Vo zP$;@czJY4GvL5O4&S-*$Vw%?7bOZ zoEn`WdMP;tp#ku_YHH&~cPTi}*2m(NtDIOc^{E`aA{AwAzjZGdD3gJfeM|XGm<#4j5uWVila* zuG4v}PL1w*ncwJbvVcBXNDUc7SkLVSXF> zDz`M8nyTCW90`fNR)Ih4=V^JQce2vD9DCCt@#~0<2y?LKw)i69mcHrWGwvs8K6vSFt@5welfmNcj7R=3V}4A7D@wf zDE|Nd-5K+h`9;kAWK@IVy5Z%WN(C&F_1Q;?hSOR zI>;|igoE^r(;A{X)C(x|_<0W{8MtEFvR5`}^L7zDZU-6DmZj@H7&Q>WeNw8dTN>t* z0YD3Oc+!?<82CVZ=}*X1Vo!@KEowOBw=(*%r%O;Tz*n--$E)8y<+}j2CXqlIYkUV= zd1GwWe`5Soiv@P9Fj#X-=O3jkKLc zT=YlfP9e(2xOH!vbnJb!(a)tVXS(+D`XF(!1fvb)JbcUk41j$%9G5PNBn0+0!VTyZ zp&x&7wOZx|bK=Re)6}s*LVk-!npijw0xr-ls~l=yzPCBIi4g6FP1bPFRm0YQ%iMb5 zY`N3X7KiK*{ZRi|+|sTzC;)?-gchGeLAA;KzRwR*aeWDMEWat@TLUfRTFmidK4=mI z*e?I_mHRm?-`sK8DC`~s3=N2+h6QCz?KuCGl}c6nI^2)CQ2mBSBO6Lae2{0z0Sqnd zXpz^)`<0%dt4V4-0Vd1t_ETlY|H2_Zf4FQpKHC7S1fSaYyR=J7q1`*9>dV4* z-0vkm8xe$&K2@pV7USMj5%TqZH9&!G6}|wb73-SD9Q_uCsbvuP>t$m0w5zH2MloWozqlzW|*re znFg{McDYNKsLlt274Ljq7z`_*U|yKiHyBFt3qpQ}gyA@B{+pYDwJ_s{_Edl;Q@J+6 zkj&?gW9`pv3btEBHpqHFJZ7z!=!zydEU161^qkrx4W_%&2pEt+D8r)nw-z$|xj zUT+pVjIHX*VU25F+X0w-^ad^SVc%G>H^bYbh_ni)kkw#zKHGr#$OLRU)EW7Xp)C_Xvl6I!%hN4FxYF=RpJcKhLhTDlITz(pc(kp->(`e1Ci*p1J0~I1k5f9 zZ!{mg9_TXecCJ7g_R!m#UyNVPfznaupyi)s2AWb;$JFlN`o7Nb(1om1d#jRndl@BS!(`dG4-#B{YPf<=dz4|Ilgt-j~WLiT01ond-pnR z+ZrpUKUj=I<6zQM3L6BZDnACuh2RckmiDQ)1N`G+TthAxIp*Cgy-pj}5p^l*O9}!s z>xTuZ#l7&ur%_)N0+m?*AYWz~qQsFw zX4PE>6j9M_#}UO;>MXD_|Cu}=q-?f0ZD5t11wGN~;dR!1QBrxma$m5&a(_(0QZ+Qe z7xxAg*SoQ$=CkB-QcFb5&gB#|V42sA9Vqfq2v2aP!&pv=r1v7TWcx5*DnUvjFpWKf;9-BiG0M)Ht8Etiaq`s|RUm+xgw8TPkY1U^?eg|y#q#3&eb zwoxu7i9RhxzM+c8o$lym`h~ut@OF6z)@>w2|0VV=T@#8dK^BGRAcY2Z#Q^=_-Hyd* z=-k717a7~_0rZ36#6xkaEs17x1@x2~N15yr#T9$_MVEgGU1R}ay)vefhIA;+lOt{O zSuo`u8GWpDq7uOyyFLs9DzdxvW*gsk*^kJ6pNlI3Um3eOztw6BUD4_R2{0&?lrHkI zdSW;}k9<*q;Emgi+7ejO=~>U~ZvrvS;P?5Ct#>tc)-xVig0dUXI=B8bF@gl72=V5C zyJkzs1v-6${^0Eg1NzD`LAP*b7)3JQEzDu}Rt1KwerzYVjeEAe{-K zn|}=CKC@qIT76R=erfbpOy103*i#TRMDElrG1Y7qA`+HkgcSY739~VMGjHZ5ZYRb* ztQjO$4}%zf8B^xJj2kGuw;K^akN>Xb@wKh5Q>P2cZV+8)^SkjOa_CnPGT`K~<>^6s z0uFi}^@e~V65lDH&-arwGHaxxhDrnZf6jb}6B``a0~sDICn$L{WXLxukc zG*~a0+p(o-gP0+%5=PJ#n6*?q{pn`JPi^6*%Ar;Spodl5tnwqUbO+c`{RXwN%LF|Q*nk;LJQvZ)bUS|?X~S_F8q1z!MpY(Dg&bnt zk%@Fb%ljY{_@WK4!Yjnba!nFI_lU<)cR(@sN?qsq9*x0}^qqb}P-+4yhIouplb(x5 z(x+t~;j*LX3V6bDL7yK>n$Z{+1Upu!RoLPhj-x{G&HuR4$h9d= zg*Y^jgAaT*JIT%m3ipup0J9cXU}5sx!vRQR5IS)GRGV{I{}nF(Ei)S|YlHjF169-S z*xZmGn@6nHdRE;(-2H{+4?vP*VofT+6{S(21TwQ-yDgj~aRjam=rNola0$!7H>Orh zunOcxBSMjzm%Wj48{!`~o=BPUq^QTzZ4ycD$V?U5igqjasQvMSCQdDSeVeuX=k zd*Q%Y4twhWZ!V4>eY=4-jO56;wF;YJLzhk`<`!)W`-5}u*< zGVBoV;v@D@;CS(4IflMmB4TOEYwiSJxft|A{F;XZBn~NHkh!`R46saCZ(lB>EIfo` zzYzem9Z<5ByS*8eh{^<}uakl7s$oEi0+=z+tpM92Qk>s2u%d&-y`M|{Xc3~gfwbzE zt9m~b1@kR9oaMB~U(&uTWU~M%5`O7#J{p&z;;;KQ-G}^+LLav(6C~R%sEfUJ#sn1j zXSl$y4-6RqvqBpK*b;)&f(Eh_gLWamG(CnK!BT3Va{wy_o#}+;uxPx>w*DrQzT2;Bd`xAK*yyRpHz!!_SD5vj%HLfy-Be6y4)qg zNF2YTw}b~w*u`YYJRved)Zz_m>5P@ezGsK6ISUhtHWc=`1-n(;&pLu4U=9e;i=x5b zTM=PrQ_xN1sTiDQN;O_jb)+tsv*d}$G+nHb~R`mz2*HA72nqvm!Qom?+jL|!uB zw}6rZ>WVjrzqTwvekdY@4@zr-4`jsHsq$fJhknk{I-KHF^_UAi5vi+iMn+?t0fCFu4T2f zTBfJf#8wB(4G^aRtT>6A2KX@x4BCkJk*`XV8&Z3*mGRr!T1YsK?;Gcoay%etzvB zU_Dd?Bbu;F>z)8*4C&cG_`o}Muk?CgVKg*u z)!06j`#lZ5Kbj^t08i(1Cm3@gpk>sOS*eeX(O~(|WYlG;gYtubH6K8evn_TAQ0MOP zjE2F4T=aa!yP#STY$m9PUkAnhcgxxTzr|{O1X^$~4j{Lj!7`z({j-+upP&I0fWa#m zvf%Ik{`HqtT^OJR2tS*!g5TzF2B!gt_wO})s8(z%CV<7KVbo0WuCXw!9tw!PgimIs z|LcvobkxsUxRE`A(MA$yX>*@(J=sLyP7lu6^!l*93x2013Y;QnJmWSZm>2+ki@h!) z(Um@rqY48m-~D-blJj`-i&4}9B^;2w`UzMSV2y-~gvQnycMdWc>c*BJ1Et*=@wmpVI%)%eR%}0U1?u_$JBS!C zE(^{Ed>#13hi{3#L#*E)@QV&K2p>MxJ0UqF^FAF|;9cntlyZ*ndumLXCGj_T=@ib} zB~Y}M)k4gV+y)th*gjwC>JX#FdV!2Tlmm8?)6lyEAGs^-hvJ%}T7t|xG1&4JV6@e_ z)v^!$hu+Jm2UHIWx+Yq0KGZGOXXqzYdr{<@t=?{?bReFwkBGZgchG)s{%)W=1Yr<_ zA`x<_M0_H!kmUFZ`}a@jsR!%AUJMjyY5~?j$E0z~YoeIuls|heWR3#~vb_)j5res*`Yh?=zMAt-bh1 z%Yq&<3&aIt_qrpDe`ntxQ-FQ|-a=7+M22^!{f11cC`RXdFQF}qFrxMJ4ygQ4h3j;vD-GV_ICyrVx<=7A!@KRCm_G`!Mud&8~8gq z_Dc$^s0C;n03q>a7i6`@D`mi!U~NQl&Brt_SEHoTwFXNgwrK%Oi2?=f33jQ`0tdQ% zo}<2ZJb^WRq=ETM$vyzkh8akw+3&8y^yfqULZv&BZFtSKQJ13i$=DQ@*%}8I-zL z_HNj>&(cI0wRuofvi4q5QXwG=IK55cUI|}i z*0jQPmGcML2=x)&^l@AOdV^9`0@NH1P(i zmDr(oH1y=2F|4kD=(G_Zk^%DL)3xbC`vVP`=54>H^e3nJNWK3JYNGC>ix4Pz^X<}) zt+ChWSX*}@lD@JxRu^SP)#v$ZBz97X=`f$2OaA@D_w;$rw@G7qlzFb-Fx`_4Z?>pD zS6MEg_h`?~dNRWDc>SpFhD-(hI?HAn1O1^yOObphI)brI5;jRl&+pD{HPV6YaJJh) zI(9$%u8&H!X@41$AIMvA_z4Rh!OHp)VvNjc&I>qH@jG6auJ0_9)$5}F76w(njYu;c zhK6+oXB0u?gWgL#`FDo+MVo$xcF>GW_jH`0Mb?6PEp16MY7!YrFbcRL2) zv$tci8t;y0{#tN(%;*$`NA-YD#4D3L+s)&qYjO52?!Gis^{(NvhypyJ=I%3w9MwlO zzx6`0FRK7FIbgMRpSE9a9I_xmqGd*z;H8kKX9^?mRijP?G-O=fHXlLX9ou3l1V_i& zrtnajpU-wsXOE8@I!C#f46#g4S!o)RBYUo4u#2hf3a2&f*I2yWkA5j+Z!f4#e=9#6?fsFE(&}xK?LqgVr@YTve_clIH}wISNMQSWF*^V7D_vrKYhTz@p1=x&0aWEb#hn%0XWk>vIL&3? zwfyjEJ$s+OVf#AVd!y1A+#Ln5S)(8T$(%cyTOw zf<+ZJ?m~X%+zSf14@UP<%Oj8={8BZ93;HLWXy^4yzjGpg>WezALBa#)5n|()NNBjU zBaG(*)UtP-b#jnBk|r={igMbdD5o?wf_<{?9!hlVDjl&(OiV)Pfn=r0vUp||jY!=| zL55gi1b2@lH zO(=VB2dNPp>a#`rb8dtUo2@G`K^?c>Ote%9`%LND&pqW(RK&$yidcfO3`5C@X8Ai( zpa~)_G0e$}bw0ahKp0RD~N-2Mm~lh7v*Uk+EBId%XzxBdD1DWcp`oxGi$nuV>%@b8e3(#Va5=uLo~)+q$X8{rq(I@r+f1 zrm$_UUQE9~KE#RM_wo|x2l7~aB_Z(wE%7k;VgKI-{Uob!O-Q<0#ZBHQUDrZ?|DBuNZvDqIb3pOJ;fc5|ograwOF(C}FXLl;DsYqNE(x8z^>8?#$4-)N?TfubwYxp6NG zb#ip_$Fs9rh?H{fnd80LI2R#5u$S0H=f=}+Bkg-@H7+K*YGofqw*e{1s^O^@>)>&W z_0MT}yE=bwY`Rk0zmiUVkWSM4hH_d9#+Tsn*RBRcOIdJO@A-ZXU$SWY!q+Q$fU71Z zK2pq|lQ)h#)rFl8+hsyx{@AsU1NN~a1D^DB&5%?rO4b!@Bp%PiPd~LeMK&EHlTrn9l+t2AmZkO&iH!wI|O(S+Ef7?{QF! zAKetoh*b1fItk&a`F^qfJCYK+wv)CGVz|U2=aUp{mUv#IxV1*iEJR=UiD zXG-qUtM6u%-Kg1HBkW^FQ4#!)VR2n%avu$3!jF`vaRm^9#ZXO;FmzsqfI1$S;jEV- zwH!I})T}gzRdc}M#lZbEal>|9UDK6 zQ8ovxOPPnIqoQx&TH&eI+e^|OOD8^j?UFr90zC%KyBC;iI7p-P8#OpGMkC>5TlJS6pXLj zj2E%)G$5>1lDs)po$Uv?9p~F45cfGsWDkHcr4!<;L;glt&V;)(7kc%B7hgkZ!Q33v zE}rLooWWQ0ZQ*(E_SHP-rfFyPR_9+vaAPPF77zCgP|U@KOJow0lh0j)0~Kzw|K$mx zSq(p?7q7Gv5+jL79geM$aY8>K?t|N0CqJC>jLt|kor}?)PYyrm4`0xZKcc>B)ubb= zQMpfLb&N26nE=~BtPs)kQ5}p45-|!qU<7*VXTGdu2>D^F$`C=4n1O5)j&$E>SIotBr`Z?vyZJz@r7rUy$0FiIAQvW_&V70d6 zr{A@myQ?!jcy2*<2j@_zXaEw_eGwKBrxRuS*SE+$pUmmZ63t#}RqYDpS+&O8w4Ty< zAM(D_@8@%Cklimw3s`^_KwHP0KX2x0UPJFFU-$t2k~ED0xcq&L0CO*-wAy<8dLOg% z%v3}ws%$xKAh5aTErHBo6xt_G=Zxv}Hq)@WT9HNXLGV8-bX`lR7wM|!+)e`|ugY8e zxKHUGjnKz%rrwE4wvCLT*G>pf{cR20G~MRHzn*OY#^ z{4E*o#|4S{iN3w(KhK^!o!+Nxrox|mdhrlL-rTLYr1`u5$Y%FYzi(HjqqM!{;atj3 zk^;tdg3i*%l!TIrMg*FC^&#@M;dvm1?VXen6S}3#A~f2(NtktMaks!uy-y&YFO*>pxTe|%$Z z>$%B`JD+^ILZy`=wc__v2lG_l9WHxOH7F_Hp!?(UTvG9)*FE`l562Ax7p_7A|75K# zMfE6LFGQF3O_Y~Zt2o5x`$GmteTtKnH9N;!+)%ZDKH*>g%3oH|*Wn2Tut zIzy_a1&ZKg+x++8@?wfVbfq;Us7v{@-uh5czdpBfzn^Ris*v?-v-06mVo_*XW&GIS zlD;6nq74#qDDS`(kP0g@c?suNabWft+|q0jCBq>>UVP4;ESKFG?fTYvi3CoG-cw)V zW2+=qcnOLH?jDEHL_O{6ls$B0ib`7vM1aNfGX0u)ALhycV>&MBgEKFkuP9q`7?>r0 z-agkyjL+aLe_!I6ZvS#*g)W^){7A+Y)qR~Tx4;@do&q&i4SyGI$N4dFp9mjTv$*;= z!^tPFR492HaDEQ}ogSSwiiKe^)B?ap{8iqJW{gBe94F8Gnn|N|$C3Bxlzcx(2Qm}x z-G`>r<@d0@%SC7HckX^V{>AE?-=auM&ES#N8JOd7#0+!2&yzqC?_mfeKkQw32?cjg z&4X}IPd35aZP{ym7W!nVJMUu;Zan1}_v`YGY%$7m`h)p)PqO|lLUsX&l;UYDtr&j0 z3n2_T)OY_C&N`I*>kKLOWIwb^@p!MD)gu)ydEn)qjlQ|0J>|jk@`Jz^s$%&eVEz!9 zqf52MS0K%2CJ*?*k=yM4I#7B*Q<(m{MUbzc8gpHM)#Y2I7+Y=6XZztlfORsK@N+L8 zVKqKb{C*}KAU*}@2J7o4T_4CezOmnI-wXGCM&F=r_v>UTXVzb`1892;|cULL|W)TX-hyN~K{BN-Q z|6#Rz98QP*_G8F3buT3_Qqz>hXQnvMmeUn1wLj;9sK#!px*<4k_%Cr+!E=jUw>d_^ zW7BFy(iY*sRzY*U%rKVXJ&IFZ8E;u3{rO}r}m-xZNQn#vBVXQlzE zn96{{K5qq0M=!m(gJ7~I8Dvuuad`-YLA^w7KSz)Am-q;%___Nw_GfSSt%y;@1_4VY zf4?nbspGzu+}@xLt~#n^Z+{*62tPWX_nhtFGw^;^pE)e(`{$YaON}kH_M+o&54G=F z^7DPaoNd4mcg4pC>)-x>56gYQT!8OTHS8|iem90!<~P#gBY4ewj!>MsLHUTSzGrq- z;mgf})H3*%=J|tw*VFM^oSB?PEe>ZEi(03CSY~?HKs4s7^Lp^WL^b3ZVc|#3 z&*n6%t`YQzlmvsj&4Q_AkI!dNUmwy+8+`5540mx`gnkrl>wEz?lZ46-*hmjJB=PI_ z;e_Wq`^W41l3#Pk%-{wdS?ZiUTEBhcD$($D1fg^)uGiCjPXIONg2YWFCQ4AGH97Z9 z;S2oLUkR#uHorCA1ft{jk`^#Vj1!;%0zL(fR#x*fen|SwA7B2iL_V9CL4TRQaCKdNzDg7!GB40Uhiot6)j%T50OdX&2}Y;(0ki{1TFrIvncT z6O^dv1$*G&TJYMG##cXq#=9Nf49=o@Z{!z0W{6F&C1X)nDDB3xeJkbhExzE=Fki%s6InB&pkPk>T_x}&{d-W07R8^cwV6w#!$XNJY;XA$d}l ztpLsek8eT6a||FET89ApaXNcjtFXq%WnM;>;`X^$gi`msTVA=1g)s@Fky$uL zbJ05&7_{-ab$+74#8>RdU46tvmKmMP)1&X zzqgMSEf0V6U+x#RNH!-3!F)QW?=8fo7u~XL0RC99A6`t7kU@eGqU53w=Ol>iC#dix z^N@QDeU(jwH0sSxk`ieA+}~K_(uA`IRV_zfCi6VRwP$N(mmQA7r<+kk4BXp^^&rt8 z4r&GY*U)&f!WCz#k5$IvheBha>8eI5m1Vw|@0e@V`++HV>5z6i>S&*D)<=BQ2GP5< z5~@VR_ot|93NLSXJ)DrHU{Bg;YE*K)?t|>IKVW2AX7rzdmAd=^Qmii6Uwr1=PDoCv z2h0~G!SetXv`79X38?QK;J|1#eshs{qUOY5T)?FcZ#$U2@}1Hs5!a>q$WaH$kT9d#fNV zdTi5i6~^=Zp_x@_9h%z%=DXZfif-h71&EWz{+!c=C`8SMCHTruhx@M#4vWIVY2Bx@ z1M?{oxkPp>YFpFK>lIJ3Segmp1&v?bPAaTeEs!=KT9=|$y6=KbMmHg~CzX0{%&jBk zU7tT|WTpU5?fz-;QLHaKj;fjQbMjlm#wx>7QQP@Tjh_GZj8>{#?)}4p#SBtvF_O`o z%zG4LZc47IrW*1KszxZ#eFFoBdTkvncHf^3wL^nyo8W7`&ifUwZWgfTK`kTD6~hIA z#cg&kKjdtuf$6hy%-M(lpv#QS2>Ik-7Y~VQ+J5^}iOEn|$_WIO5T1<4U;QC({1!*7 zz#Vd+UQ^=g(sv7T)kAhl993{0xtS@{>R$Ckwri74K7Y~sj2Tt|4~1t zWJJ+=c-MW3&ALfQzsrwUPRmHYu00%Lu~oc{*(RRad{TKx+Iy2Z=t+*Y9X6fNCT4Oh z)a;i#pTp_+1H0^MBwr(Vk4;Bz$1eNjM=KowM|cg-lI>^ABVX$w`Fcuy$nD*)`W5_x zY@hqi957#DmIHA7u$c6m*M{fBolOYs(3SUXUCZz7&;%cr((1kYlNh!y&k@}`YYf}H ze<7+oejazsD*I`A?FesZ7#}%tSwZG#04>XaNdkoh#vg+xbe~8r7US=p%KIOZY z-jeO27c+H!&^~L9TgM`ifDPs)R9OO&I9Zp|`)!yBnA%iheZJ+lZhHJ|=SquiJc0sF zyL!H2f#G&&d9y7+SA_cx;qB3N4@ZTn6%OMrPyJ&(SnIftfJPgY=w-TC{Cm9a0`MWo&EliHPY;#sC6eNojYS-# z-kNoUSCZgNWl&!yB`fE`;U0gWL=x_l6nuv9W>#|U^f22D(INh0FC7g4Bd9k^2`@*b z4Q`Q4N`hduBTCye)L$Sr~V5wo3b@l1WRN9|_Se z&*~W%jP<4AP(=HW(exzi>Fxz_emzzseYsR$!hX(Y4RBvm$*z*WOIpOO&3fwUN&DTS zOuSpwg`ns_3-AW_id*|a`Lm2!Q#GmY$qTcu;Tu&vTID0(z7>W#^2AoHzpb}C4H4&!|)iA#$+!S z(0|7w*Qw;Qbz8?6Y;Et+Fc!__Jc?V`>c1_DVUSM7Taa8NAD$_{HReTy=JxfTCGgZo~apT9}`7Cz$*+G`8s;dg+`L!n;vME{`a z=C52s991D&Y}|@!Xqm0vw!c{vV_%CLP0X}w$YNGWZZ{rs_Tan%;I@VFrO_J&?#?E1 zEw_Gn-3mki{A7rkaioVyObb@@7FN<6&njZ-q`bfLG~a7`Kc8-=R~1vuKd7vO(Z5tI zFjy8kejuV{Usc#n*ruYEiNi0=_@vFB{`$cHuwnJ1^S_LE>U|OX9 zO~1JvE}s{EBIDAYU%e9;nAUiD4=}UL@nM4aos=~5r{rX`M=>IY4zVJJLsTe(MW6aE z=`qBs@y~UnDSpEvsy!U|D(hGeUu#Xqh^AJT) zh2QdBY94VjafkS9XjrbPCONq8m*>xDgD2CFuOw)^fkm?ap!r626UP^CZapgz@^%HR zU#N+E9PLdQuj4pIPZS)zUk2yF$8eQ0;V0`eS^E+SUsnMo zr(sT%HNRz)?n2=IYq-0~*5vSey1zq?rZJEF+yy<4`)E%B12~GmOSVmJ(-y`#hu|AI)(b#E%znH~X3Swuqr22YZN<)<{!X+b*Hz~f}|TKopS^VA?4lRW)ndKAM#hl_EMD-JBWpy?#Y`{&D0Fhyh%R;eRFZ}rFZc|YkG z#}2pgY&riJW9nB-4sc`7%e4<+aB183prpSxZ_Vax@?#oxnEzct`zA}(VhB5{YDE+m zWJ<_NWk9ZZ+&t!?lw*MIF=j6ZKSnNe>$sL`zTL)JEN!AWTBzqz9*b)=_tDtR+w?F!iQt$;u`>yGwk5yIg(=wsZ)d(N9EElTS`x$>eUJ z%xWpqo(H*G0nW@vFTL_7$eiq3ql89gHDIZ}AsS388L$@r5X2^$VyN@srgx{pX2sad z#80nKBLjY&ui34gQrveWu{GC0t`+~PZ-PYWjwKHkE}=}rx?)v1|HVsZi|)?VKH0)a z{%_cA|2kj%KSb`QZhnm2u6M_A{ZrxoQJX7asq>}!v@UE)nMNSr_|Gmi`>hKd4>K2q zRG+O%E-r54L)<#|BzZ>1l>~wzCk|BaV9j)~9gxNoUoO5pSG-9R2W1)*%X-h8fg0=1 z80L!$O|vmu370$H_jW2ABlu*Fvyh$Ox_uR;eqZ;L-xB{RgC?ua>NLNftW@G2+l5&V zr=eQc>Ck?Yar+K$G)B5lJ&HwZ^MPJsftQsmtZAjWd3yZ1jvlZWRWaP8}KdJ?)`Jb!O!KJBe2^Xriafm_B8s?jM>7({K8+tpJlF2x=+c) z_+DVZJ5>AVJkX>!@8hp^Kd$>_{?ohvLBi~bZWQEP@k5gT89Z^v#0#Wo*&H~Uuc!ho zVTfTAMj;?POf36GhD5y|J+ypW>7Hx?+TvdOxNR*9b&RtI)j#@!6_7H&3`58k_=tI+ zjfXXbftSAAl$)_r>ZK-0`ZG4o9n?+q3&{(%_t8L@8rggLYu0*2TQ!1o_F)RX5C5+# z557;wC~|QSqHstSw96aoc8d2nS?||oM&E)}@Lrdb^m@pGp??Ag;Pgklp4s<&Q!yal z@YXhWZ~3=8?DsRfpWYB|3mSW>iaXaLW!QT$*vv`xBcXRovX{A+56IEA`_@Xw7EQ$| zB2(>W?WYRGey#R=iG@FxE~IDj{@`5R)RUMhu`B~O<0LzJ3OnKT0RQZxB7Z`Li_`b}IQ-fd{@q3_-#yO( zzrC^;(Th|*a72u3*2ETNa!N4q_j=ur&(b(;)yMcqWA)>Iw9FVhN6n&w_@8`|(ufADQ!Ry2z7ms8`x7xg#jNWZWCXncF}{8(_qsLYfY7`qbX zcw-XxP!B^Ubak#vU%b4M+`4#R6b4O3pD5!{3+hOTVt*w}{F_Di=7N6*pANV&qKIrB=9&J%D7yb*WX$OIuzD$dfq9G# zr&kAy>FK!2J#+wY{=E7g@WN=|a3HX=$+TBg~nyOoO z$VO&UV&}zH`-Rs{*#DZit8hX>O+*?^3zWR}pE5btv<4qPzHWnU_I{CxY( zqmPbu5s0u&v3}==M8|DMn2@P}Qp&xr`SVFo84q3Mk30`_spFZqLv*ZB2Yz=^h>lO5 znG-tiF**U_rQb5G_Fc|~4%H&n1QIwTI)ya`+m-wj+N^@uyN=gnhQ!I+&p4Fxj!t|p z==X3$w-_|W!vm-yU1Fc@`>pBs>kD|>LFcp@;tjZl-ucZFW13U_(@=m-$|>yM@!HI7 zEwzoa^*y|~L&N)(Vze4yAVg&EHE}H~Iko`1GN}?6VaK+<8Zqlf_X8!S31`UsTNo{r(Ah^)WzkVsrzEw)z#@lXT&p= z>I8uvHk>pfS`7Vmu0Cp(HhPI9v&X&(`nT`t`C|N%@6Y~~@K2V-7ujqxoS^(7AJzNz zd|9PW5{5)N!Q z#F#2RQT3MX9C29NDLQ{&#%Q$rOvK`0jJ6?Jzt`VB=@CP-uHE-Kvb{@S#nRZ`$UxZU zaif7!Pja_e-oB!xqjnE(;S~Wh&%O|zqx>UaEl7`-{q{N-%M~s$nvEDAR#Q~1j;Hzo zdOhEkM|hJ6B^o~d;pSR0E3otRf+Sdeul8j@p$r2*tgN9GaTP$>PME_)s%!~Ke%K#z%gCv;_->5n} z9iQ7a9NO`3_JFc4jKch|+~-#LUEH~bFGOn2;+_Rej-O_5^Yz0%=rO9BRP}P_mZiLL zR{0f}39JW}5m1%iXmgBgA6@I>h2D0%Z1TG<7-tWG5?z_eXS$CZ-S$)wSz4eKl7fsxM1sv(d*OvHL|+| z`|W9)C*xSru5ge#v|ixRSh?{C?TJSjjI%JhbYQPf{Z^=PiY@? z|B-H*X~8!NV{W#{{AS(*h)13HMM07<3Ec9mWc|C_*VMJf@ z+j`}1zwW@>{W^&lb>E0{;H9|_y`sa*;v744fs!B3L3{UTmDi(}tK-WJF{r9K zy_zSmmxB}^#BtV`B{jSjtj~G7zyb`K>Cy8o|!fW?Tkjmg(BM=}!eZkun-``J&k3=ATocx^ix;_Fv z#=w?87WL=>)~z3#oNbUH<|-h#*(k1OUOhVKot(ok-Av&v$-{d9VCf~44$m%=`uu)# z+eW8rBxFzf9gWk}YJBKm>o%7Ql@;}9@$rBc@`fm&apT{ac(!IJ;%(9k{P-v0DiU4I zZe69^12mp)#t*sd9U(;NF3}qT^bqTX>0xf=`*;7v&m$0`Z08Q=mm&5Syf5jIf<0N0 zLW1xl!Q;g6)4r(iYozjR5Ktl3+w&}i7CM#9KYgOFT!F1L;ang4>;6*PqIa|VW#ff3 z0`y*QL}XLDO_hFVh6fRRd&w@Cl+Xg9W8jDX##(5N!+xHmgzN4HVlz$U*4~2*x)(8q8Gk}YqkB~vnz5wLt(k5}u2ipIn3t!p_A&Ye3 zt~JE)&oO58@V4&9dEo4NvMuAReHyf`Lo=+YlmC_^pqYmJXG;$*>QHRVLri|Rj(d<-U1Jt09dia>MF^DgcceS#5m<#YyM?TWm;hNk_61VD;aqTT4>da z^TZIS3nrMrQE`8{deObeC7 zHWDp6=@%ExEWS*rqPrWq;W8BQ)l@=}foRQr&vIXhU+)90|CTMgU7)o&@^AgxywE#4 zYvYdLVRD7466s+g2*F%Km0ud##{j!xh|=6}9}yX%xBV&;`y<9nZGMFL!mqRH zOid9(zzIWras@V;9mf@ss z<~4YrbI~}l)NLKk#I5i^hMdw4hD;gq>bWgwpf!xB*c|DwK8~H~+Hf45U(>;njjjb2 zk+tMUhc=r@>)uaIol&=UJfHP*t0&5r^H?5TKr|VW%;LCAFHv0>>-W=y9A@0lQ#N%w zjNUK*rkrk6%y5LboQXEFGg0lxQ`eZV>Nt01<~bo%DF~7^>5`xB&hneE3$_oF5@1B;Vt8{NX~i< zyY|*ct=b*-bvUu8r|50hdn`KvB(dM`q(FP^_Y3Z?j0OW>;)y9;2FSo|q~3ZDXZ3V% z)sG3{||*@_ z<;t6GAHW*?bkI2Qy$|$HNTeXRt2_f^CXth?b&i}+rKVdmjne@9_Z#!KXq;C5RakKF z6x(l8L$GI_)061+(#4b@JooqPp%N?}>dpE(R6ohVec!8lMV06E_E9COly=pk$gt%^ zS#or{ycJ_`nN8H5Zx|tYM@udUMHHXBJ5%&F>O2_lhd%l}i`Nfu#a#THKCJE>;!W`& zWTfq(Z(Nb)Lpdr*uel*l6W4MDx!cL`sFT4uAe#fP7W7R^*ZaZx~6PURoo z8O!B#R%#90CbVzK5+grs3c55ZJS9UC7B^FWy|05w5U>>_EH(s}`8BC+0lW9n{gUz1Qz!6@J z+H|YyhT@1y)e}Gpd?a8uuTeUtf9!L&i-kUOdcie(j*`kb=tdfyDSjJEg@ul}{|59Y zpXsON5n@>k^v}$%%XSixT=cmXWuvE^KeGJf+55!xK3QMFLImWTW#l@q#dpcr^73`E zZN0`y>OKT?y%6r@J32GUN5>Q@f(D<;ci{TJPhZF2qRP~T_krO)bxU^*BLH9{#aeCY zxV8h$E$j!qA04zEjLLZXAfalLN^k1mFdAM0dUVUnpcJie@V}b9ePQ+iSWt4}_F#lkj zSGbrsesHvT++9*rEQdO>>XzN$wd(C4^9X0qz(8jvJ5H+VdK#WR$zgm}_1maS&(uE1 z#%31%@d?;MQ+*Ftx$LQreFVuoZ};3_cK4eh-LE+n(A}*us2Zh_Q9mOe8|DO=0_(+rv?Gt z*=x`6&=hf%wMs(A>kWuKCL>}&^ku*N2r#u#&;h4XUmvcgWBo=a0bNDw`7>@}@mGN; zdFWcAu|!4iK71g4o{S|$Iir6*DPW##q@$Ie_P>)c_D^T+W#!3JJE6g>(wuX-NLv-06x-fb$TX^#$j0M})4CmHar)9KDsQfzW;^UwDlfu!7Nj@y||!6DEkyUzYcBEu0(UIc8S> zW;CwL@hdp8{9ATxmxkQzpRi z2^FN{+D2Z$5EO6qrF+~=k(oNBuh77}=a~Eg3NH56MgUjEJllSRBPsv7lL9yKE!s!0 zcV?nV1ipzs`bV5bDIbO_a#4>x>y1V>B`L!s&YaoBF{tEZ7icCK&g#3U;*R&ii-p^N z1A`HH6%aK4RIBe%E#0rdoIQpAFkbhj0mz@)gXr7vao~Mu@oLmZb|9GM-sH)C*NAs? z^r@cp_dMQ?H~%*Q0`Xoi*#QXG+>OrQ-d%6Min~{yRHjgoK)29n^-63S;E>01boj*Jl3AHPj|yj>ITt1u}4iNzfdZCoOJ+ZHmfThx|H<`}0~ z8q9=VxeyMd*M)|V&w3E|c(1ML69|@Ffy<||&GBB=BD+tR*hDXR9@?Azp&fAOd&Z8p zQ~N@zR3rcZ;`UWY;jNj5M&3ZxI7&mTk#i|u54Yx{3n-RkRdD{TtedHO4>~`CH@t6H ziG=GMeLiq&8lX|PNte#gz1}ENeWxAT>npNgyilbVJDq`nLOy-ac zdAuIAcl|!1b8LHf`c8d#o*(<;#8g?Y`QSSUoc#R8%jx5gzhIM}7}?a|$zSik^t^|b z@Lv}sXBW=%T1?2As*h0ZFS0^<$F@pNXe1n;Qa3_V9SDpBD;Gg}!AE9pLOP3{}KtAfGEb&@DhI%J_9P8|ly1=E z$=}ndx~iU^Tr25#(s!pr`mn^iR6=hnCgUCYGy6Uj%d|)Ogy_+Eq8E3qO2!sU_o5w_ z^D^}Yf4`!m&K8Zg6v9U|g!9~Y7+N)P|0bd7d-b78v$slc(n&%8MM&#CWWBR+)z(2B!p$m(`y)5tIScOZHf>>^k5oSUqIq{Ny$Wt|OF@m| za!;>gj};VMzdS}^^+#Q)gCJZ`sl_X?vkBnClcw8d2-zVsOECHkGy5|y}Qu!H~SH?SfB>!@><#kJI zFeUV(op>je1;JQV9pNuNm%e(UKQHR@Hk-GP-=-z{lI)|AKvB6^sXty+t&t+w`|5LF z4NCk|C5VUR(Wjx~%N4y&Xf&Ue8^B>6<|rLA6HXN52v#sVwJ;hL_;8Pc+{+3$gi9XKobj z`ACdTKoolC$FmlXvSw00+bB}8uD>V` zxsUQx3WD3{h_F>qFgh(V&I-T!`yj!h^m1G^`u*PHpf>~QHpQZylS39Ga*y_$5cPeZ zEPhm3*FpdpZP%)XRXHc_n38>S*9Mur3d%kof90UDUB)WYPW_;)!GAutnkFtp{kp&R zxI%rQoAo;DZ?iup}5CIBnI-yZ8rjAhWPRC_s3;_pz)=m)3E=zsc>VhB)xG57X3-kJNCSiP#2BUm`Z%So=o{^HhWht#~U(>kG(OjSr&_8447r%2PaPc17p zwrir_*5e+eeFw*SfGk3^n5Eg**r52l-R4XLj`FNsUYF?cY3{E&L4oN|1CnM0P>`c# zP^PUmanpXf3#rQf=wd0Z4FcM@&7J(_hlhlnY>Up$b&%qZ(l&k$_wJN>vx^26w-z9C ziX4g|Hq{^r!-E*^g14P4C%(;-`D`70H$Uw_KXs1Oz!6j33{-!Mt71N+7Jb}hf?A)q zoMT%59TQ6y7@>T~(@&HypZQK8QW|v8s{IfxSGrq2g0^z1o?j0w8)wC9ucKBLeE#nG zS2)}U{k5T$0R)Csa|upIMfl$C=UkKSgmFSwqi?{c5(WZfvbdL%4KF3z7XYODbAtEr zt<_}k5!5$&Hv=(m0|_}q7E+>3%(``bVH>yhY&3Q)B}KfD7=Z#QF!<4qGkF|eIqNiAZr9B#r=|$XQ-NxfK8%! zbk+Qt<$HGGI9NCIUFl)}m@-b02)}nPiutA-e%5=rN2UoVbvKUpm4Qe=2Uao8sqG(k zo%o@6$lWEdW6BN1+%^&Z9M#e1biYb9A=;#f@fTt>pnpg`L@jI-5d9fnmqqR!};rjJ&CL5EXP1c;eOxh zF8fBjd%whhLAP2vecg4t{T0wW*E&8A6JfB>q`}2+DeZrfc4kfLa@`gGL~j-Ia4E>7 zBA_6{O^Q(w5ShVGpG7BmQ%R+gi&XXV{JZT|5f10zi@0}P4I zfL+J#2S`T{68gJd)Mu0Ta-NY~n0}vaU8|PsMp(f~|Ga)dUT6(^{A%bijjS7Mcmh7^ zlxR7Ew{umf_q;~BrTxWdrW=892xkt$w??XExK2q&tML13)lGBZ);QT{<6dVn+&zhW zJKoCb^)s4xrtUM$o4XNui0M|pKXc`AvtC5WpKkQ`Mp#p6i7@#5F-~f*n+`4kde)Q~ zo+npu`;_9?|M=xZ1+VUuoD}u@MCtz||M+c^*A>%St3woOls^CwlphYKj_T_x=_?Ob0DPTg!p8toxUP)+!c>1fA3RFHjtg7%&0NAtLG z@AGnk)*19#We<0HOM1Z>&OSNOe0boVm+Hr*hFt!vWX80PU$fxezilCo+KD*5Jo|Nm zZT+$8%dsbht#ar3`p8xoOBi4EHV)|?Iea7WWca!hyIn6(-Cd4E4`kf;U7*{F>=_D# z{s=xyGeOs1irxd^Yr2PQd-z-hkHxNkN@+96o=7}>7K@5eo150B{4+lXA~@fnvP#aA zBH;J?+!ZHE{CYIx-bs;=Ixf4J&JG*L%{s+4@l^>@30CDleMU^)rp_(!Cu)J%Xa2@s}f7#ITB`&G2uFr{3xj2ji zL0{N;>WO;`chPx4N-bP=7^3u|sj!rq5+-8eOVoo?+>JuRJ?1uohS!4>eX3IRvd0gB zr_t9w;wd4q`kM-qt0l4^P}N@#1km89tH*BpQj_^2tadm7N9s4M{IVS-jE^5cPcz`0 zWSfVbW<@+d*bs3B+fS4hY;6%p88&dG#e4895#f$@bm@DgaN;RzDj$TDEw_jp~jA&bEvR}-an4LnsAK$VIAlaa`*9wNkHL+weSnq;r`ufHDOgB2?EEhE{XNya zNLfF53FDhhCpGay=NLLyf1&~&{f*Yx$&vd#CUsDKYtWIbLwq74J8_ocZ5$L-v(xh$ zE+mHe&v`#GqbgsKYB>0Y7Phi7}`N2xhmdkHD(*!coacpSN9TymJ#BVui%lCo8 zH*D*#;4|JQEOwX;>WqZeo<9El>vUoLKeL|e!Aqv@|53?+u;{eA2Xf3 z%hK$7lzkTV_pT-Bmc_=STZG}00^sqxAjtB=D=Xi`15(#3!5$jRjiQWxN0&UZv3$Y` z30+OO`CxMvO$Q$1Qbwz1*Rc}1ca+D_)2e#s~w zAeO|t%hZvw;^X--Bc1SReceO~6_?YDZ_Dc~w%TiY-{sOkLHw%MOmQ;8ksGhv`i4h{ z#7|_5Eq=WgI&h8NX$@xiR$kDxlkLFG-bw2yI8>Cy!sRIvP_-i5x zWZ@Py+C{5-z!3Pu9B5}kZtt0My)R1^B0|LrR>ecM*Y7=_-P+fheU4c!!pzIcG&aH+ z{;jl(kXuDRa|Q!paXL=u%He!)yUkUj>5(?!ZkK{+e31^iN?9w*a`q)AC6;{irEA^x zQwr?osmBz{N4fQh~(o|+SL_|a=N~X~`?9NdJ7>veT+ZvSo z`=D5VaxAlM+vnkmt&&nWo5oF7{`=EK6nAv{4xa&WW3CqfKj`C`1I}}wiBG!kfat{}`%C!j&^>@?o zP}PLq`pByMd~>hp`#=5^G@0}P8fL zniLCqnfxk>;xC==+pH%jI*0QMjCea}k0;2tYZE4xaw_q%_?qH?Q<6ZQ9XNe*0axyx zY1h>mp*T3xKaYCK=xfq8gV|u&wKw7ek(`O_ChJ+>f3D4sJ1MtmvAt!zD~4RZ4M#hC zo~eAj13G?ECD(%S>)_DXGRJCnofu%RDf9PeR2mMZca#tF8>N%?CwlAzh8^=zDE8VO z^+rw^OORGxcqc7}?KPEk$sQ;rLVpyukEg0*YJveI(iKRha)af&tU5#RVUJExZ6U*KtdhsbOw<$f0M_ZQ?7DG zo3Y#%b^(x0>oNFx))bR+c6sbE&5~+w;VhknI|@Dmd1TATdxL4La_U7Tbo;xg!?zTU zpCUR)!aC4lJdqBE)o-ajL;5_nuj}Xa&BaeEQi(dFgQZ7GmOV(vQarH2!In?{w&9@h zwI4olNZQ+_cf_mgrpM265DX;I-IP1o7L4h144MmJ)2wqEA|gp%mZ!tOX%+xe2i$%L zL17T0Hm-t@MwV${gH;kBqZjY(UHFJ*F`CtrN0sPc4JcWnbzPGtBYkeqbYCI9n)PcT zR(=5^!cGCPzMmSc+U#l{Eb_;3CR)J@iatsUx*2iA{T?J<_b{9tZLU0eKbY9;XSG1B z9sf86OEL5%IlB5jcpgRv~xq<3I!0qpuWw5j3cp&zF6e{EmxKZtqZS zQJF+)io8VbmXbRC`N%4tOg`&l2a7+HrN|lf0Mg2iBRtz>G?rY=l(Ka~pry|T!L~%f z_S#ff080r0>tQ2ie1FZpPzFrUX*%h0 z%sW)!Pl0yGucPVeD7p_tkZ>T)HzzdudwVwF|D~q;pS@!aphQ4cHcN`tYJ~rop8G!IPg!@Pqip8_H1noO;z+-^pDT-Sy7#zy0bSRJ{Vmeb){bNC zp8am7nQAbW;T%4eN_)r~d=n0E8=RA#hn2>xj{AVy)NN6zdW6otF7Ovbxy(;!CU6S(IG~DyZK<6tN$dB;l}Dd-2_!ddq*P z0ZZ$2(wiHaXvj0$HCu|nCjA6titK}qvI`U1Bd%E^ey@AksmcJ?&wc+U98+3`H%6rH zTOFC08Jj8?*iv2c`8o&%(fw}Nqd|01W9X?DXcLx?xDS4OwX>6~`DOnEg~}IoGwhKA zPBp5Myux)vx7R%QYgS`fR`2xbu~0%YinuNIDeG{6jQ?SJbaa{yX7FS1aP)^BQdw9Z zoM*cRAQDwP*cn%kuOfc@2nCv;j(Xg;(k0?eqEUYPf%oTW!$Cjsfj~0W0Uh@xP+H z$e(r1X!PQLgqef*-gI!N5Mu93Zgeq;pBU~}cWXv-?nv*MAp4I8AX%W3*Ujkm*<(_Q z?$+&bwJGF}Z-Z^PG@&gwdH^o{7}I@T{szT2Ep3kSJGL8}tgpM<@qI5BKg09nVJiE@ z?f11}RH#_feyLerefjk9yv_tf(<1CcGyV=(&GhF*{+K0DH9>&@5>F9g2D*sui}$%$ zS&b58d2}|bW)u16_#7=L7xAlqupYg`0hYC|^tk4qN&@e#>Dt>IUsVUJeXSg|7h5=hT%2f8D_c2$bKMgtlB3N3 z$Ll@RhYAiPAp}ft(7Gm{?i+2s)cb@!+FBc}}gY@SfzN;pr zcehW5dBQ>MEepngAjm)L_q-n)w=nLKVR(pMbxjT`*WKgq9!e$3F`M0Un!)q*3?yVv z+vkyZZ{N;SK7}gVBNg*5^K+!z&nL@UgSHTfj#5%E4MDBn^2RCK=$|^Wp*&mbviThNV;{Gx474z$1 z31@RZ)6+}Oo{n?t?F|kf^x$m@Q1z*e-YE$if4Q^ajQQBmvFAOcw+wETrs&O!-f!s* z*LQqHnqJ+TRnJP307IDb4(aAc}s2; zcL*%+bTlQ8T82O_^Y7w9RtaK^ui95d9liVY%~K}_ZfS3n?u+tJwR};=bTZCNo&DrjR5@^@;6*g0CC@jC;lJ<{ zw`*1Cs!M`hKv>90&hQT%gm0LZN**l0r*z=7QKd9zB_e9^@GlmKjQiBl3 z#G|j2UQ;zKpI*bn?cfFswV&;Y!<-9o(gjhcVH)D+uoZyJ+1GivR-+MN zf~sR4Q8}8?hVY~j(n5UuaeA3Po2!~1;c|aVuv6!dV>sqFtda)=Jp+uj&{Y_RCq}T{ z>#}LjQ?}1mjeFN*k9Yh}3q#*~PCyxU?!H6g^;E^L<-}h>qY0ax;~;rw58Xxk zvhp+RWo}&QUBA(Li-Sa#t<#4$?r^F4{r1DPeh1?yBuCWwDo7~&s=UR z*W-^vA?W!WoAYBi*%>b%;%5W_@6m@zfV5PvP6;+7qc`*3)dxr!Y{PXdH-y;ruK0CM%0H1sR3>tQ`q(|Dms}V^B(obvw-NX|@RoS4G zMG*RiDajq~9#LOSO?C@CSW&_21#d&8aNL6d%QsOxri>hRX)o8}2P@?AN~baaq04W zt-7c1Q^{{d(##@+OG$^4CX=7UazJh;no6uzt!b34P1YdvxSF+Lm><9xz2Q_QI-;Fne8gNNe#X$xWEKp7F4PB}A7Ni%a zD1e$IZC5T&zNAdfOz@1~Knw)gJ*lUg)&!DLqVk%iV_){ZH^FX><+qz56@(sH-lGub zfD$qfSzF#R_DMO7jVPZAs`(|E?`5ot#NhsT@y$)Nngs*rGzR&688;)oU7y!OO^L0W zwAzH6yCwQ!2%GH1Dd8$khW+y!_1~#fuX{L;C2ipmS_gV2I5(-S>;Z^V(hxyFQ*5QFx^QaU76zQIAI(RzlfB>27cB zZ65TXT66TrP8e&l>ud&HpRT{p7nLg6$s3({hRmf>H1?@Lk%kCy55t}s#Xk?kr&NK9 ztypwlX0%_dK#KH=?iK#5HD^+-19#AVMG=u@P$dJ!#YHe>RaUOoch;lic{g7wO<}>z z3lj04WTAx|1^(I`_uD@$#k@0m)LmeuyhLq%71i}SQ-3^#Qh4Qu+JS!kY+sqPaoY}; zH>Pvpb~z!dcX)*eRMvgcc)XJR!`~lNqD_3rmK_Sr?YsvfkM|xK%eN{z!)VLUS4*w2Dq~oWqwjjSS`=M9i=s-Pg zvQ@nZ$BGzuhmXIb(At%84!`}uq)#{X@l79aq7x_7@Yn;W-0Ji_q@tus3IS%@`_Thf ztmxzBRuA4TrHcY}!xgRDC;`8xFO=>$>Yw<+bT`3VS;SBO_GQx)BX+UZ?twLOt@RU) z!FnwQTy%cz0bBw@57Hi?rg1q`rw3k+k#ylF2*0=AxLD7!A^6BmoJX6{kpIL^A+wJv zyd9o+#T%ylH?mIeP0_rHr7SRebPIEubo%_finf#bSFA7gpb-dCCES2?3UUE?O3!R^ z+R!`n)w>h_&Qqpke~3f))5fr5f!au=-q(f>QB1|IN11;hJ@S>fsv!H^K65#=r0IxwRT7R|kIdeOiFu zm;O|4pvcH}9hb0!TFx%0Dqn`QE5KUzb1SvYc0D`*GVs0fwKRn{gRhSc->^CYbeOf< z6wsMN2?#t~(15C|-x$&os@D(2k!Ud$KVRyHU{bOa`J0|#a;&aTSN2GHl1Ug$@+>; zbt1cW9VFS*$5z7N&^uvjz^gIFD%))*S)DqVftY$YyuL~RKIqoyMYg(OKpLCLWfRAh zPZ2v7|4$KoH<8nkj!E}c!J|@2*|VM@cXp7cgFtBnmw23Hny#=b2eca%U*Z04smF5F znMKD=I7M52_E4O=1`9eZLki&%q;6<9LTChd4*AibV&6~9s1@yJ>wU8NOi|&o7{k(o z|K+bjvQO?!@6pwvKYH@<5@5#uu+YE5qyi;t7D4J`s?R!!%D{sPeu8&upLf~P)ArJi2xm({S5_KV860i67XQVc#x7jT4>&buORf}*U=%!{@CB{c%WJ*@3`=F*qJ4Kg$!t}l%EYer~l{(Hn*xaETpk_TYU%qRYCuG4u z=uHBhG;|ikpZpVn6pJmJ#pQCRYv|w{lsJd(^2?z2)GG2Ke*1N`axmXv(V^VJ6b`Oo zrGwS#_U8!sJbG?<5=r`!zu}5|lI!EwoNBF3E{hXlF+QN{^b4cL%bv>mx34&dlL8Vh zDNcpVH!b_ck=`yAW$tEj(xkhdR-Vq8bAj=Rc`Y9HV@k}0TA%)jo#mt6I;Z7&d;U!G za76=X?B8$mgUAaNBnQo!sPRINd%p8M?` z)ppLlt%01eoJm9k*8Uz7UoVhR8tk7z@5H&dA6bCQ&m}-!VL$E}xFuhU?U~GK`F_Z4O>Xu`J5|^t}th z>r=j+az7_XCLGkItZ-&k&wfHp^@t6_hrhLdj*g$qo}A-)(>qA>hW0iFl4KzFe(j&s z>tLwj4M2+RbprzI((>dK!T>2)%MU&JCGw!o^!{EH|I;J{daJQ^N|VGjG`aES_7&DL zwNE4L@Tw!f2*&8^%s!pi&tF#9vNntRw6Qmln2Ae0geyOzLy|__-~L4pZT`K*t4+RL zu5Msisojr2SCO%HeJdsC065B!+XzZ4X5DK`7zmIgF({n5bLwu-Vp?xn!(cB2fRwO{ zPdDc?KJ&YO`s*s*S_2 zIzjRAN(e?K@}sd#j$?Mxer1)G-9@oBGD|~MFAO#eeMS1@*D9(@LqgQ@bv8waZ?W(; z{Ay{krzukU2~WLxSo=eCM%?F>iF2K*sXZ8 z9U-HTJszzy_+S3Q$@6}@?pQ#{3z9N9;l51p!w+mp5XqoQq#`#J4Et6KO`61SE9b}X zuk8X@l~5*V>_Qj~V!hWwNXLBhIO#25UnL=QiTj(KDQoyzgF>sn=rHiIi~Dxqw4}L` z`4qqY!w}@lg-hG^_T*P)l}hdvgiY95ZFbnVIe^38zwIM1$Wpu!^?;rlW6wrl?k%!kOh`_RoFvw_X3L4&eCkPEh|-Bs_R)luEIaF*_rxt;O3V1 zcYqK7g-35$fyC!OIdLK=_%k!&<8hLn2FLfGd+a*<)DIShpmj6*9Lu{$|8gI@`-Xz` zemVXwV^AN;vu#M%QZ^3v-r)(dbdJjB^Lh%!@7;t%KI{5V2)N8Xe&NCi4<+Ri@YtJC zW{Ghsh2`F~ey*@DyDR7JS&Sw8d2A#S4*T?mB&F#bKd`8$FVzk z^kNb5aR~NMw1=lXEe`!CkO3cj@#DU2_m;nFcLoWxxC0$^L1#O4QE)X2q4C89f3|%< zk^X#YNVujRhW2`P+FvYLez!v4+bq&Q`_`SD-}`oW8c6SJ%gugpJJ1x!HEaIhH+T*< z7li;y3m`6g$Gzn5*@r!60WUiI0k`i2pphIQ7qNh;{$p*qWD@Uv!s;WtB5Uwe_U8oq z27F6j2GNp5p|f$qW51H`iSqr_lT`Rd;~{n2rd2kFq9>ESPH;rhy`8g> z^6Xk+m`Ty*7yAo8dSU-5fNesDZ}7IG7!B!uwyzL37AaNWJ=A5T(6Gmp!DFD!=DnZ7 z&42u@T0kv4FV8rqo;!t4J#~;_41CY+s}D*~f;ZF%coa7o)K5&HC9ylI41R~6p=Ffh zn|5vs`76^O-pn?Ee|SicwEfECPxkdB4;k*p6}AOv!e>GP_r3Ty!rQGlZ&NqqrYA(} zT#EC6upA#jbs@0mE&9~mACC*z+Q^$D_VivrOx--6y1&u1E{;<_UK5aV_oexP@L2pB z%j+1*mM0;FrJ^4BqxZhuY7ElfT|6oaA92c-WblE>Y-)xT{JF5F12;5 z@x@Ff#Ub%6{ql=70^g5nfCU#1`u#efpOwdzm-=ji@F#;Kx_#xYil<26S5gTRg@(Bp zZeuf-Z=9i#$OM)2<1+0_e*JzAo8yYdPkfy3wx1LMy%yiFYzB;NDPY-sNL`_#sgm16 ztMVQ$-s?W>PscY(kE_>uj^K5C zB)A2cfV+nv137^xIJvv3gY4dK={io>bqk1c>*ijJv08xl5ax;UK_Wq$Q+T3@0bZD3lgf8Qrk{qr34 z;{b--KK5X0zOUNBo7Q2dikFaV*#m#VJy@Do`YS&GVb7-2C8l_@eiioOhU{tFP;(Wp z&#EeJ-ySFhn@`3~d~mxy1>9dw)YJ1>o{j2TauyNYlw)A@NO=U~oF}_?3+x`hmr<%B z{!87eH2lRq_fRBu$p-1yX<*xVrsUR~nsZ^(D90!9*5>49dxCKx7A_M8Sa5~&lT%^8 ztnydo%xP4&FS37=&HfFJ#3J3P;^$Y=2+sW{NN)N%pC1mDP%o0QEsf!V;@ys63bn^IJI@dIyw5<` zquAI4nJBTD5+QLAPaG}e_Glk8EalCm0A*sGfkh6%ziX@@m8DNkF4D}HP0=$4CCo9~9y#b_nmt+G8;rhVVuCusL z?I0HeRr^uaIrP;jPw>#^>XhvEayA-m^KkiH^bdTZ&G{@0zo|Kx#k*5p+xokHZRJa31k#05e{9QxON&U4 zs6X_oC(qAmiQT=m0h$gc)z15!q^iAu0N-I&+|X*TDr&-0W9Ep|?*OuHwkC%}>`|7o z<6+S!Aas_+-j|O{FdR}j#~P#tYhkdB7(`&5LOgVq^UAT*Ym@1cS+L{$%EGjohFKE8 zGBT*!>B^(WuX(*To(qc`uLL1!@pqU@Q-qVaK2cwoSihB@6JhT~IZVZL#JD|n^XKeFGp10YhV(0W3 z954D#u%u;x5yuPguV+xypm@%EP=UR{UWxtd8`%LBlsj+si)3$066G;>6BiF&nKz4A z=Ppg{dRsX_g94%Lw%bbm{PX1ifT4U8Vc9V5_r_M9bAB14H-9&^`3T{`zCrC~(B7YJ=UPrccqb&*lzKW0Sy zA=-sJqxgCrQ58NcSWD1IL(OMPMTnGQx|Le5qkV8*tFw0@UcrXXH-7C0rX!If3}|>7!eHYuspA(4EFWxH&B|qq9?V%fK`Kg(~{oE+pkhj zQ^zl4qWSN}EZW0UB@oT3)xN6FhhudSjSpT@>W(>WSPY$u$yx6ok0aw%a2uN1`(gjU z`hj6a$EwR?u2d`+!jbmC7wir`?*yLM(sxMr zkP&YR`|Tw|xBXoH;6t)+O#(CUuJ9&BPht~h3F5Na}dN_o;NgX)b>wz@hq#obW zDS@f!aQnRzBux9k-T2>?xy$Do^ya5=hPv?1q$~ZT&YyQb_-N_*WIEp&=L_srL81V3 zUVvwP7brBC`R_(6o6-Bdzf0Hy8YKeXkz-m3K?hk z`DgAT7=aIjH;vmO;>})^RcPa->K@QP%5>EUI* z&;j%4sC{6$E>WQ6!=T)nJco*w@%qExk3Fh2-upGLJx2Tu+-a|+1jLgiOQxT`?~Ffw zc#REzdd*t0^0eKfobkjvMJj(ug0~9M1`4R~KLEl z51?AcIG>_iQ9Bl+Pvxk-&H6uXIZ)I;<$i(~$9s3fnc<5N&G*VMxwJ13l_$MQu^z0Z z5m7@VaD+}31ybUC`P;JD$B!GXWwQtF1b>-T_#&xJ5|-qZqc|*OQqQ`-wV*`rlRTGS zsz?UBwhQgaRLhZjMtAHxRH8zt71Sa7n!6i|#$o41n$f;o9$Rbt^r!Qz2p0=#ic;-4 z*luq(^i_}4&xU1B-JCy^pMZN4UmH3+{BHXi97^w(YA(Nps#_<7s|8%+VQkEf;Rc%?elg~&8whUmRs~N{bW&3bz%idQipI(av^5#W9 zvmfS`Kzv_4#9TMt&!9RaQuKDun(UYv2nG}IE#U#a59iF=+$DG6j&kbT6o5;=-Kc{X zFAqi6^66sx zo;B>kR9)A0exk&$Bh?RyPd$teS`lK6>0lb`BLGr&b6G}@$uFw~^K+TqlZQ5d=v9`a z1=HR$^kk_6-!3e=(w)IBPX|+SXaRnD_rM%*4mw9}C*wxD{tze7gyS{c#-FV;-+DY} zuk*B33P6FYI+g%_UJhO&9jq+ZVz%RT4;BxJ`<&8D0R#?PM&9$#a`Qs)HML#kxr0&A&pw+=K#k^lnIH z8}jvHPd`X4;Z-I{jAkjTwfa>!Y|;cDU>5-;uZr{P#NG+g=0brPU%C#(Yht!N|EJ0> zOw_VvQc~t{G7lBKxbAcRyjcgJ`wBN)5Rx#<5t`Jo8vs2$u7Q+ap}SyBQ(h`xM?5!7 z=ctsZYnB*x#v^(a-0KnY97NN$rh$ zFJZ^PZV4j^Z^7ns{kL`j?QlOf^xbtUNfIQ~vDB)8)`3v1JDjbnk92pE0P;tVH=NQl zGX!tczTU%C=~f@?lZBo9K5+Iu1DNbL?(jW4);rdw!sYOIJ9fG`5XT5A2J~5y`s162 zaMwd+;wbA;ET$<#H85>K<=vJ$n4a$YX=t_WZcd6=I3wNGM?b3s72g1S>ikqyGVR}K zue3A~C%G;&O!}Rs=MhJvG}QgNc3t`E*lWSvpMoyTqh^My4`5FV z7`A4y(L%d@U|3o=Fqyb%9}YdVcC%X3edYikx{YfsftBtb6U%*;2@%9+^ut(gyS@*$ z5*-M6y)r=7-Z&NTPwly0qAd|%UGRDuMW(!bx$-^-+J^^~(6wyRUfaIJR$Ko9#;Bj& ziaZ-z)Kb`}B`S<<`oquwb%zyV9HU!(C4N8ORy2V;DdmAbYujqG@%J_*SCHA(hNlcb zqef`REFPfiAuOHQu;JVYj#EPQL@C{#$9E4@bNRh0DKZbpS~}lUyP3q0G?h5`ySEwg z{>O+v4sEi&iM_jDx~Hl8%kLG;QFU)KGK=bc7V68^F9bVh>h{~8ri4dN?=8#Yz&m8^ z@UAi#$E#mZ1?eq;qsiq1>&5&zZPx2aA~Uhiskp!xCs6}DG>vIns(%dsrqw8hDG+Fe zC>Z!Kdc5D|k~cP?Q!tRv!E>!{Y!#wvp>4W7>rCm zt$j$w$d`GDfY6{(Va1s{Hs|^l=#AXWjwv(MWH@-==CdZAHsoJEvAp3Xkt}?4a(^`l z^hzVC10B=mrZ2EJN4IarjFaX2*>sa>bcGHr<2CvdX6o5Q-*0pAH{hX(>9*igeIstg zPWIauV{XA4DbMfABaa_orfA}LjYXq$E_VZy1UP6aka`ZD6f@t|$rwRti8&^+8v}3p zDf-(rge8aFU!ZaE@#*16)4een4z-rCsOCr!v!;&-i5yvW1?ys5V~JBU)8HHaSR$Q9CN$pvXvY)g~r81G=IQgZIN)#mZYg zXX_aW=Vs}w))Om4G8d~Q7v?P(DDJJ~(RpV?`NAZqGnD#FW&l~!dD?gLP<9NVtPNeLkXZlbiKQ-7PJ5Yt$VlcHlk0EJx@Y}* zbzXz0oCjSC?j3^n26YKer`EDcPs71MK4vs9uKWo-(9?_gHZG|=D0bg`T$u>q(d)+R zGo&-oHz@_W$cp4M=S8iH34Lz)f;Vacc2BpO5QeA?a$aYKyUR)NxKm1W${s_1pnVEb zVNK-c`K*oDK&j>QLKG|6jFJ#18x`S03>MeZJqPurdIQ_7EQxO@#v3g~DI2gr$DUrS z%d7PBJUs}MFaK}m_isu4Ke;vk zNu`n79eG3SpboY6!u>zXE9vncIt^>!)4) z!wPc*2`e*qfeyK)Ei0Lh$2}|3p@qxs(Px zgF#L1O%*UxY4h&3vZoweT-^ zPKB93{e9>%V77%6&h}ZLZ5~4nsz&D$_ow|#+1p0UoL2B_F#Y8&XEY`48+?3~NBBwb zMY06^D17ziw7StSI(#P67YqaGQ}z)zYsA49A;Cvm^?bp#Q9I}&@K4dGo{F*%zFK}Y_dGWjNgG;lI+UZ&hbo0=U1P>Q9yxM*owgF1??nt0s zsGUoHq&__T-j$)N=6tQwtI2I<)<-W%F}YTaW$ zLK<~D3-<WIA8a4#BBrQ^MARqc*G z`y``d`H0Y!iNC+*k3h82y1*N#HS9J%duYPu57xv!azR|HlEs~@9_KJDr54Y=>GJo zI{KVncq*xqGCF~()`U5*FlM!$K}GQiTOlsD^(IHN>lCB~6s|TP!u?vz?{*~?HYI_bt=xoBaM)f{1JkBgE$$9FNM%0dj{w#dVU6@mfg{8+3@SzY*F2LTk3uK*g46=U#>7Ub@X2 zRr_zK;c<3u@a?tnpnJl7fI+)U89_EYza!Me^F}<=CMAsixM##9q~7;;o}D^Kmz*77 zeb-Mod=+BicQ%;r9xgl#_NaZnZ%jf`>ZAVm9$;#OA21lyKP4p=ITCnf{uID>{18>edGFPfJV`c(PxFE}8Qy3Ji+wHcM#y$2Qua|F^UYqU`0M~t=8!*?P%)bZ2j$R<>`X)!I4kYk|tvPe-x`FdWbechR)7El1hu&Bir(;t(ay z=91$gNp-`07@zZ66UwdYe#7S=V`4Ayn1#*kVQcnK(et;c)B?gncj2b5^I#0SftI3I zb+Xeym+3+(Wr`UiMm<6U2VPh|VUEIWukP>h-2%$-Bvd3D77qnQ@aY{nlY&0PexjCc zoU%H~M=(L2zNdGx5Q(^ZJm~bxpd&y=f)y{q-JSwM;05}!P>WD<$iK>s%TC3N2HNYH zDeddft@_xN0h0H9K9T-)KHM9Mp6_^iI!1&Hv(2s(=kl8H*9R@J!~DU{;BT-&a9Y0J z_r(a16l=<0yr8)p^u`yOoWYABi~ytBIK}!YJ5Hbnxv%yVD<>E@hl|CRPgw&?AK&&4 zquiYI0PpI}M_HCb@oXXq!M}0(ePlid>ibCHPEk^<_+rsr>v>P*`YUwd8qk*AYwdtm ziPq)&>adPv?HMOR_{3+$^$a7EMSy0-7)&1iDvaALn3(p7tg+${7sKdN!rMcYk4Y6Y z*LwR1)l|`Vz2o4}P7}P_D_9d;k{ZNzV5DclXEkgpGNM^q%Bj^=1L^{F)bG}Bo%MiV z@{tt;g{DP_4lpN5`7g17y^W){DtSl(87DaIQnwv|CjE4~DI)mP>cq_xe(YVA12uDK zcCmFv=EIzp=?IBDpcS8qgn@vTM$4{2#+QH#_=FV!N)Um|XQg7k)4&tc! zIX0g8mKyEeFMvGidEXV;%_|cG+*ucj==+thx!Tv`BX6fcMnl^O5aYY6>7#nOt&vxu zKyOqoQQLfekWbFHK&hr)le2kpc1pMOfj#niCj2e^?zxnp{}vZQ=wEk{Bqn<5B4=M_ zU<51f(aPOgzw)X5_pCg z42Koq>Y-mx{LNR4oc-94NW-Myy~e2SK3+T^lx#lA5qpD6#%gtBz3nrYyt3pt#iv?! zJLEI8(|t7k-mjT8A)lrbYsLFVnu_G`4oQn>gA_M@CLY6_3qT&6EaDe0&v=D69N#yBoLHL@f15hgR(Ia}1&Vpq_=xrGJ{1TBu%WYiG>pYDAI z9jivFC5SnmuZ-jOa}gsghX#c#3C@|S2xm3BAo2d2QS-&0-<*)U2CV|e>Tkf&FlKQ( z?@<>QI9OI4wZA}eFDG$6tXQk1@i8^)_YM^JGX%S%=Nqw5OJ-KH4IVVf9@l>HpIA#G zdKOHSI+^tKo>|V0Fl*3ywE~?0pBmrUpLA`}HT59Qfa>obU~c87$<{D-eU8h$e<*v9qQZ)1 zEg`^gZNK%eyJS`RBK3AO?_xl`_N$WXNHIXRa5>isM=7~>BiL=e9$rIju8|@=zk|j$ zPeE>{O$fjYi1+VPLHNBFo8H|I2=b6iD|+dcRNfd>zZ!{oaTtBy%0m)SJNHqD0qdrZ z7JDQh?t8%>oJQ((S#GF5{Z2GgzrjnXm4i~ts-*Ann8Io&sh5y;DY)N>pCfHw+Q$i# zuNT2*QuWvs%wZ(n4`s8;_gz(`F8=v@f1&~TR)Ej^Ih?=o?R~AFXS5`PV95rU13A4s z!kO{gPY7F#7M)HT8t2a{IP(4dOG__ieoO}5D_qX2=uLx3&_ z#v~5+tWX&t4N{FXM*Jo_b;iWRM2vXfEtT78_w@00Exwu_ky~GWTTQ;~O1Z@^o>`fF z1`1!3aLW>d+Q%k~xkm&TwnN*jUigfJXe2dRR#-FsRPp$WWF?}BnF`b#Hah@h7*1}C z^-7>#NbBxs1ws4Apixuj_htp>m%WL{J2cu8C)p3rQc_P^bo-`4Wm8bhezICUhnA86T|cjmZQT{OafZ%HCu<}WCY_vuG0c+O>~)7pOk2m z3wU_s2;7;{gdag+a#Mf4o3Py_D)Iw%xqK?TzPGNvv~xALcZDi3Le)U0$^3S!Ap_|4 zsb_y0P=&bVuW@72A$ciBQg)!%ti$I8Blosl9;}J{Sa_5lWrgk(O}e|yK2v+FRcSO2 z1MM<Q{VsG+(Dk#dILKca-%jIA#W?nJmpfMUOk|yM0J}kd1{^V^z7w zX>9lHXJV~Fa1ZSaV)}cH)FCD!C?&tgaJPG8hIi0lrZqzEt!oTcT+h0YwuHPGuwA@W%;-(yk8D3W)5E*@LXg!b^XiWF=9THY zgR@KwIWyj!Gxiynf7W&c8nuXK+)l&WEG|M;nedTPA&Q4;N+%W&X;|$02K%yAKxH*_?yHhfoNOJ1>?tp zql0hJDkKWshZ@vuZU;1>gDDZBAIv~zBEMbe>sik?tq(Jzy;y5d=j<+5?SGJRAN&LF zJKnmSgp^{yCrA?>CR`BCe!BCUx}&|E2yX@8Q*!BC*YI(8#ypib%=hDggvTQ8{YaN| zGMV)WH7-~=+i6eFX=UI^P)mZxMOB=d5Jgj9o|W*X2cn@i*H}+bG(AlLnx|2-E`bNfL?}m(fEIrH#AntL z?j#sx_UTk^s%(sxElpP{Zo2QMW#7tG8*@M9s#+~#`K z@9hebcNpkJ73!{bSz=pW0E$D)Ej;3iEDe;NmC~Wd4|HILw5!iS8jj4@!qUUPj zVpTx*$?fZPC7i1Zz;&ul9WN)vlpK@TPNiZhPe)>CD@kJ$R@hesQ<5h^Nc23N@|e78 zx8`4od-rgt_wIkV?Ao1oB$W=1MMsRmI20LX#tdVe2ayLLA@gaAH3;rYJ$AzY~cr-QCT2a-d$mRwr~ zE8N%0(ceTCH*}*xiy#MC2!M$SCqjFEAdVg1HryEkYo4rdmmoIG$c0{bE`HXwP6iaC zAe@ywk7ZA=q*=P^vG4&jKbAp=D-}jBQ>iR_2A5+D-C>x1Y%2j9nuCFcgW7NC%?ozE zJss)}!@+F8!q{po(GqDOWCn&Au^g=ZoS`d`HJ(QecMA`5i3oA`$D)`542kMy12I}O zn~n^Qz~4G{lDUJq=mTc$>mt_PPhzI~k$l@GMWSBS~Y|JAOp~oiy z>c_%dgjNEYJG9xyIAQ{=+-xvbIEEjX7Fp2sbw;nTtZOCGzc!aV+TS z=x7i^cay1LP*G?nBE-DV%n%yiF9iM&a0DzXs;dh`fYFdUG3EwAKYmC6KnHuY>}A{l zKf-XZ2`7ZOo9K~Tjr5_m+y#d9+4u&LC{7fJKssPd^bJBeG_nf=Z_hFI<9Ph+fe*!W zXtW(Q*xA_`heq4d_0SQnzGxICz(q)adR~uEI}*W`uJ6fnrl4>rCmS-x&VVXIGNJrn zhBC|66-m;E|JhKSFrHv8cyI&q&k5eWT;0V zAYITQdIF@UzKOjjbYZhM^bl& zK$kNvhRt;fH?$8y6Bu?Np=h2pGJt61Zs-~U&CG zoWqb1UkxBLfYQc1te%i!$%!C3g`!ZTpBV|bj3ToX0Jm&~1z;&RJPhk3TNmIv5qe~Q zV=Ro+AoKJ|2ppXn6oC)M(0ql~FvbT4Pv{{%p;q75(Zr7IY$zZELnABC5Fs5h2Ekz= zRvb63y%ADoG2(4q4f!S*j8Om=Bm~QFF?NQKC)U!>8cImX&JHfbKq_QgZFzcBk|U9Z zA)wp{)~9dsDX_+h|YI6Ih4j>EzTaA^C;5r#Rq zaP*7}(E7eaw?HGIfZ&YAIn(_G!9+_xmL2pn;h_8@pxFgDn%4gA?r4}UWPs%G?I?C= z0}mU0PXsO01>$+VNpLp%o_Im?g_~ zp#il56E1_njRfJbfmeaTpKwnT+c2uLBi70v;pSw`67T@*!r?%O9f@P6TH^f_`8~1P9NsLt$OX5cCQ&!u{=Ar3^95fCCkWM3LVG?5HiJ`kdSzeeY zn;QZLzJrZ`6HLL_^8NH286+c07_^lMNl9 zh5`IWn7gr_%u)+BAUJv83?UjxGjQZvx%is6xbev>fDv;r%m8~QJ7Y%<%~W%-ByEG2WJppnoj(3ffla7hN*hDFEz z44XhbY#8)m@nsu(Vv)fCm=HHC+Xb3T;m|~wpyY{hAhKNfe3&0@NH+#^goL!F8?#}) zh`R&B@#k!EV`GvY9%8m2vQ~jqCm6QKg!Z{uI?dh?i(>yQf|O~00UD`q9l*8n&=Eb%ieustK;|RaAu!IxDKr!s7+Bjvp%mGW>4?^MVdH&+AhOD|G16nBLin;q z3t^4|Jt`9gdcxBoh~i{v=?0CFjfosR7A=%TN3r}U&U%4>@<4HLL_drGM{{AhaRO`z z#*RT4Cf`729e_FFLUtsWcp!rLc)dUa=tyD!AF~L00$P9z^s;ufqgfmH8G)e?M7Oem zf>0}c0?p13bPn2lt2DGsM2W68?|33%PIPkXEhx$Ujn$Vwzhe4@WnA$5#(*L8dlH(_H zxAh?7&tg)bEud^X<9}xUkrARr%N&4B)RP{M~IA)%EoA3BS>`wRTJ zcxNJ&LgzSH@nL>FEZEA?*$sl-Xk37kAGCi3xxnI`Au!}1J0`7+Q9_1g1lsfG+#mxz ztN_3iJVQ$eZS(2&VNfLEN_Hc=T7vP5cHv_6T!~aTD9HA9{?;6fr+^N|PxF9w zQcRexj^X$-?9ib!jK4pQLSWm$kUywBfwl@HBAZL)qj78soI=3}o(Y=e=Wi7h>KIHU z8T&%5g|Wau$i)XngoM+P*gy;&CQu0N`A$|)I}%283}RqBZDiJn9){!+Zb)%6qRMi% zG6@f1$V%WK-lgw=u!jg4e8iS{=qxvTdxpQPeiqB~GsfCL;WEq%vtgkFg1NGeOwg<* z0CXNCu~9_md~Ha?<1pbAgaAVgWrj0od?CRdaJ4Q%sQwJKBg(>zLAD;QG?{8(MFd-W z(EX6kRy0ni9>foAaRR25(2)=0j$i_-9X<5;1FOqwSn0;X>R`Z*}-%@EX5DXB4ClIAQTg!7wkmG!+6F(OR{sAm6J7* zj)KDxD?191SSO)@EVOF^A298ShT+E6AzZE}-`^DhZ52XU&@MRK-^QP2#RLo`{Dvb4 z4GMzcVJ3Ws0GW=UI#|Qi_;6QD03z6!4W(=hs=h2h>0*fIQt>=iM4&Jzh~QxFO0Y7) z7#kbQ9tLACa5m7AE{sJA59YbUCjv{Oun-e>h^BgmIbuCs9GC=xz$Q45AAn&{P<*@# zS6}EKg213n$Q~gGz`q;gWi@7whC&Pzj(cZT0EY>^N@Qw25H?3bI8V^#GITw zi0+V}Wpag(JR$Khw&0sNxnQ8`6Xl1&67`I6wtfKter$IF)&p%KD_+I=V(`%L1=;|y zd9rn&EM>jC&;(~oKN}(dsktU0mNc}RVW5Mak&z&n1wE5FmTr{LP`?Ov1fc)vRA*kG zqnix`46KP1fTjIhX z9d1MR<L$2XklY2;)BcvuunA$F&_hSFU1(EfCPJ)sNP2!f1;1bu!G2V)8M zab)ED9mNZ*eCqB-a zhs5f!tRwvWLj&zNw!wN(CWCYKHKLl(pl=k1h#_NOC>BL#$03PheSKU96u_Fr;j2>!0a0%Sd{}4X3oKs2@({kk*HW`cIgHk ziaag-o%O;<2(Ik7hAt{FtHIxeYivR!aM&K6t~^6ej$ufUA3it)j}-`*e!dj4bA&H5 z*oc9*q$3TXfE>s6XSnOb5KIOSV+m=nAU(Vj&ePD@T1XELwQ&soiHx+wtXM`EggZ{(jmU*V5$jAgbl}?~?9hI)Zv{lI6WfRZ{sAt++A1i>&z=Vp z5kg({;i*=R4kUt}p&%F&OeGKvB3xM^T&K_wA~Mt!WhW%ELZE4j6Eh?f!Y&YP3wCs( z3G{3OjZOF_dK_pb>L}zHagl*^geB6?-6;@8Qs7{4q^o{-1V`VM%;j4l(4oP0IDaTR zb@tWgAe>1iM)t0PP-M8jp&j4Tlj>p8E#JG;dTM+t1ywrud@p*1Dw))ujnW`y`1Tm4~>u^CRHNtPESn^FHoJkeTJNT?2K7zGiLt#&p5StV`%BT=Bumc z|L2!8=UUH_7X{Dy_s{=*rM%wEs;t=5`lf%}?qA<`EjIu4DgXL-mYi0sMDbdP$;yAO z;?M85OYhJ5Z+F{%4^|;(q=Vb@KNkP6OC!p=VG?dzA1-F|wWbhy2FID6AayV#=r*x2bzEraBjlUuW-#Vr%a zM2q^)sq&Vbg+H(T`^_GxJqx?3)I5Bb{=j%)o{Y@$OX3V$ms?8b)tx^z`&Z(2sK-iL z)_lG)A1*$-4#;>cVZ}eGWh}p48WLM2FC%=18vJ_E$1C&xeiW?u%Urdoy)f8u*37xH z&}xgtxKBSE#!TerykGI_+Xk8vimWtb@^V;sL z{zFdwqJG@gD%I5Q=i13f@9w^9^$W|WnaymjxPk1RC%aKRtZ>6DWb&^(r4}xiU~xb5 z_;2VLa<1!QCC;w(*EzrP&XHtz`0c^_L9$&ofLD08@Ym(W#x8~%n6KBLBioeKb9>aM zo(*l9V})4vE4L8rV|O>ML&>)TH+;06AFfFRHec{F#5LN)UfKSA!((fg{`!>ISXlln z*(U@7EFx#0?~Y%;zPJKznxvdE1hn`H`|Yf{gXi=sEqY*;+N824i)2jjo18GgqBvss zp4wI!Q~ZnQaY;+gwv#c7YD&~$%jf+`kEqJ`dw+dWf}+~UoGcl`IXJ@jzOR=3x+5F0KmfnrDdiwL(SPn*zWLNcy!tOpy=(5Xp#?tw+g4d?^;3S&U-F6i zbz5h|eV0GmONwSSz{BH`6t+t*9l!rd=hwylW4Gi*Uw$Ds{CRKA%qmsYr6+y^`fUGW z)`+~QfBfj4bH|tbn_e^I)@g5V$U3|#VaO8pR>tQ(?L6+kcWvfe$=X;+ce)l2zL)=E z1Kg--m-~-BNu8%Q_577&^%^<(^(dLZl|>(I?;QmBlTqkTvI%8xqT+G_I5akP4(x!6 zn*Qv6efjfuYOpIa;gkO_yW%i9=YQ+2fZmw%`+LVDhM{OL7&qX1cn5vUF?pQ<$s!9$42EvjIW1NG1(22VqOqovpaGsKei=Ue7J!t6?FSZg*(3A{kDTs z^L}J#5%q#LT6(E?Vq@h*&_q^PaDv6#L;C8o?#RD8{CReEDPCT5=bXPr@^*N~0GBFN zvQu@6m2|^C-fOa@bVGUktE?scFF&jjD@=dNofhV0?Uz`U>JHQV9;}qfc1Dxc?VN71 z#1#cB%1@uV9H=>Uq+X??Emb6@$B#u0EB~KZM4F^~%?3sEy#*kBx-0Gympop#rgEfr z$xf~L)rDTZYE!okZ=|j6A|X!ISIqAsz1~taRVJLkO7BmX4T#DXeoa@B3^5vV_+e-H4x_%BZVKoYv}o6kTxr$A^0I+0$ptzUd9L z4tHO|nN1F6JPgl1pQ8>*RAKXuEEB--EHFV=uH+==B^F~>2FnZ@B-4Iq<*mow< z{!xmurtaM_rz+9C*qPimW}a}eQ}eV4KIT4Brq{Lw77kTEDt#M~e~S0iB=vSKDNCoF zRYYv(m6q4wRHI#%ZSh>IofUP%i{FIN4}N#=!1$pLGtT8izZYppe3mtS+qz6#gLKH< z6RRyZSG@SICz>ON%(q#m77wSdu3aXIGCTg6^5%73eaa{u zi*6_%uGpm5sH|(oo-SlB*q&ffQ80Etin>IkWiL$}8=4Hc-E;W2RT^nY#`sR{rfbz% zQH&23o4QC-Df!pXr>j(XVihyUa1|dn;pN_uj@0j*t(GMqzwhhKcVPPVWY)JsaQyNoM}oApuBgWebOsEoTwWdeq&2k` z^YO~`Z&(-uBdO?26aRxc83?=toYy80p=?dE8)8v7xQ|n9p}^OSIxdx->xGEX5~1_XsRV ztBacxq+b5HETq_XP0{DFtRvOQS?mO~7QsfOYRd0hUq*lbK)WYF(>y``B(hI$;tBn` zfreK+n-SIDq9+5*Y$P)$EEc~y>%Zth|6<(jdFBd(2 zF=ShPdJ*c4!+1N#qN(<1y>8_l^_=6${XKQ*nAzuAeMH-mScpU0H{OxHUo1M9oo4R& zblW#CkFbtV>gPAN56#@aP+7xj{~xJ3H@@GAiTL_)o%WgV^InldHywK#Ys|;5_utNv z_GmW^Z*1!~AIpwZHsSh@4Hx%k8=R}Le%EjQl~U+?e)p5vkqw5etSg0;>>G7jP3C8! zM)0qrMjNt!?2Hmur~b&V9ecEjV{ks3pQ3Q4Swl3)I3|(Q>y&TqD*JG3hhXhBSHqDx z(+{T!Uze+j^IUp&A>|n|3pNA!oG86MkZDk`1=UH|={-d_^8LagM4z_-=J!Qgt*@Ry zZCWDQDf(fk9P-h@B=XIXea7b>Bpo2xPL_3jtnayyF})(uy7K$i?$o&|-adURBi?*j zAA!q4bq~5Al!Q-Dard1H{hsrDZ1bA*VqMLVeoyh&$+3ZUo5}BE-&a|q(@c^Nlzvm} zL@|8^hJ#Sms*z+ZVqp1@(ZLL#m`#Kq%|{B6Pj6Wr*vd5n5t!5z_q`yKYv0`;^?#JY zsTH(Gn=T18dbO*75#`y|`ux(j+GO1dj_^r!svZ*} zukN_y2Zze{&J#gHT6}R$Z$Q}Z9i#N4^W-f_cDGBg@Z+UC zjr+L1XKA^IPB1jgF8kIUUUw)wN8`}df=f;(^)GZKDV%a~(0_3FK=QD*j$8GQssmnx zwv74YjmEFL4Vvq6a+S~340h_7zKi|MO=#bjmKUvzsI%6%Fr@v|G{2JU3NrYm@=C>- zPvKQrUSfTdS#97TwiuOpsaQ)V&aFmB*54j{tbFL%=-`dc$3GV99QyH1`PIdc?9SIW zqg)J5#=M^GxJ@nfRAQ^tWXO#2;mrbVoZMmTm#U{KI(f!1{Wjs~lyhcoab?x+rQ@ogE^R|(;eNB23+RFLx%&Ig=ga0H< zutilV)up&8VtdBU@1w2(Q+8+Wq@}ExjEl`_G9SJ(nqi~Y#x5oL?_Xnd@Q~*6y0L-Z zs6`Ftu1Thr2^P1djhGKw1?dt>3Z?a#2j}kBm1u`eV*2DzY1%9WB^xc`$+eo;DESuw zdsizNH&>~)Bltfq*k%}M_;!8DO>_+DYo6Zb^uG4_Tf}t160{? zM&@Ac`tshi&vnZ#4vy;XC}AD7$rtz>l&?~i4)3{WDlP0Nz4ws!m)Xb#Co=uF=YQnN z$eLm@!3VP1_FS{vU%w@6b5hl6C1%PianZWu59cl{HkfbH{=n|ABwN8UFVzf#jhQ^6 za>-vTym^q16z942G^UnrwtLg6oLz(KN>d2&Otcs`-ohWcG3=(ZJjv&#Y2L(L)**{@ zts%|6Q@qmEBIyBcM`&fr&xc5OlS7q>gX-jb1GZS$u)Tg>zE$;rtUTG0)I?Q;Xf24(hda}EN53h6z{ zQ>}HGhs3Xc8sAg{xrgcpw}Ttw6{PTZ-Q6{nH{zEUbdG)uEPPB!vse=PpgB!J6os35 zrC`A9B6&8brXS1Q?b=ph*F$m>@2|}o?`*h{XptM!m^C$4vUTj)0)5{HvHih9%+ztA zf@oiTF|(yDZ0(sb!o5m~^V=Ywjb;5c&pVn#+KH=jd(-A`_>M3XwJC^Ft`COBe9iYU zY`%X|8Cd||*rDD8?*ST$x0MA|Ys!Ap)pgXiCvD5|>iE>+&Kss7bGsH#WvrfPvD;cu zK241#c^<$?nTZKA<@@Kyxn=NE-Ssd5p?h*2g3K}-$`zgS*bmxG(ue8tB6CK=)vxU5 zXL65^PD{nrV6Or@B}=je_MgV70b|9NC(>P|O@@~yTHda5!$OE*gwY=6{A6OHuaf~s zbl{ZQRMb0^b4_`&h2Z&Kv8frcCTck+iU)%iTiX* zvYMufr?Z9&0)M!`u|28540!gcqu5}i=K07#M|qgb3Sm3Dl)XcG!a@|2{fZBC?!Xlt zpfEcsngd2&-AsVjH!YY@>`Ro4zBfylzPU{FrShey$ZX{ynH5`j!0y3A`GmO!ilVM+ z&QN{9K-H1il($_Zc;}*1>k6-jDvFxt8&r;dHaow8wDCAYotAOc)6>A&xv;pK{4&TV z7b@|4(yo_wG}uN`U2&@u*CZA};dy#LLuOrM}b7Fr_@ zboOSt=vI4$H^iIAoH#ID+QIc$@bV=3j%WAUOPWW-46}N!0q}&Qx{Q zh+wiASrh*tyzHpLyswkqVI8h+SG``BNU}ejcE(Kyr!jU@T#v?TMd6{ za@b_^Rm!8nRQb`jk;9nD=CqE}b~V+?)S>YgSN1t+S9ras&60G=Nrw&YPn!xAO{12H z^Q>aG{tcxXSc%e)(qw zrLGsITLi0u?mj~WCKs&9qD}X`80l#tSudaHoBrapG|s=b<@@IG8m~6*w!N$3wr902 zYezoK+91eVSH7n7_NyA*AA(s&PLTTA*sX<+PiDCzm&`ip{pMy&N=yX4Fd@x^)KQgn z>di?eWfoeziTn^uppXvA=|@Me_okg*Nzu@Fu2mwTp(r;Z&9$gZqzH)_m8>7M)?H%CRDH}K+!3Oltxm4_z-h-_=gZTqCy{Mr#IZYeQSf$R{L$}QH z(FafK=X9Pp_D($aGB}F`&GYUW>!uqk&IK=Namt?#Cv~Z)OPixKK?zGmI4+?5G3lXs ze(i-l)vb1fhHHIqf*&r*K8e6SYqD9OsmE*&Qo77KRC}f|=o9;6?QuGPQH!TnUjk08 zx{>0U(C&9US9zdjt7=*TVPtbvmfu^H+d#_pQk_mKZ7<8z8&B<)SG9DESPXvwpHq{H zo*S6;7IHXbw$!-iw{HNu1_+nHwxu{1_-nl2fA^d%0diI ze}@=s%5&PcTw%vOur9gy%J&hgtgg@hbj2s@cwx6{WR#cmx+d)jPdxt8qgr)n>5D7C z*eVf>f!`c)8=Tc%9gyO|n2zkesdCBh>LH76?bOt^BQ=`)yXZGg#B=dDsdywJB6BSS zPiF7_lb2l;MMsjnFM7nM756WjoD7F?v8~HIyVlT}H$S^7p*R&Eo^{bctgV9RSu%lS zHm_Ai`0YLZpjGG0UP(7P5z(Rbte_s%MJnCmbKq+^$SdjBXa@san?uJhE=!lAnd%L2 zHug&;Pj_UWuiMD2ieKcs;G#!^s-nkebG>M3`Z(44xS%SF#(uyS*YJ-tuiVz4A!3PZ ztp6Bz?Yf;?0K!ISDb_8&YurVe)IFoH;O35FVoPLZ$HXT5ahB-C$8Cv{^t6WJ^kW0h zE^K1pbcT9fe5Ox~9OZT;qU!d}`^_JW#t&OlJ4^;I`>Pr*=MXpJXaE?b9jG*sVJi z^E-ZoeYy?2Zlx%)LzVYm)r*cu>$jXlQRwB7JItnD51t5*n+}>dR$m5kpK+JEa*rf^ z-ts-_4lCk{gM73+*PZ#C!?Yd8m|ik0=^)nIPbT?18v4UCH#tLrY^oqSd2=55TJF9> zSA|u+xcZK7Z*L~`A9+4u=UiQ!-Fi_GR}cO!-Y%2P(>cxgHWm5!@zG67%A=J9)>9H5 zM|0}V#LGX_A249|4T{IAtub;L{u$W@!JZMZ%Kt0|)dp{1{ zU^XnpU{lL5f_8R#$!xVM)k?uh)0pspnXVZ@K6pn{@pv76`GlnUQI1u0mSG;TtfxH5 z0>;pO1OsTM7=GK8ofx zkcJM`#>j@z?Jj$h)Pn5!9Su4K{~F#4_t|t!dp!Kd5gGb!vCp;{=tok;*J9S$WN{3MMt$U^S^M=ZH*{Mm#O2r3` z%u|0Czr8$z&l`A2JpSEer;*Eb{9ymOjGi?n2m8U^tlD)MtJe#Dh9|5W2Sx=shhymDxm}KLRjab@%p+5#N|IxPeP~XAak;YvUZPzdO#vnH4cxjU(Sc zAZjy`_9S7JvgTOI8Z)CM>@G*Pc%r4bVl47*g04@+)+IjtGs!w->o;ndbKc%z6j1Ar zeKk(I-Jkh6q^vK8*MEX9^29y1zx|wdyffn4=QW9*cxK{b#MA0isQOjS1@&RCHAP)a z5te}%cbTr}JsGG`X&?wdjnw31sRZAfnJ>BdeY*CLrly6Sd10g;^YTaCkm=?h#m;$~ zlRG6V+qX=Q-kg54_1Dnic?d1q6xgu;g$1x~e|ZSv?aM!q1#!VcTj_gMh!du)XYaZ7 zYm(0ocNvNXi_Hy>DC{=qKx{bLw4!CHo&^{}RXY9b#^t*5L3tC~$_GogRppeN%1PZ1 zwsC9ra`mYd*Vk?F!&WaVA3rcvnuH?n6b6q?pZq)SVOQLA2p6;*Gx@3sXEu24{>HAx zTOpBk;+jtRc^2d0(J`k(&EGoR;Zle6{}9*2J4q;D8gzh5cz#Jr|M{2Bhq@2pRG8M! zUhPiWnUtAm(a`MPRSi0xyV3mh`NTCh6_<+!L-3BvdcVnHgNTAhPohDn9$)b&T8VDl zv)Fw7y&;M9SMi7NV)x0)3yR>%QD-BS54WtZ~Xy`O6?z$-*D2pktLE9$&&6p z8ocfIEaHIPQ(-E-Dd)VJlSek~kUFM0%w)(cwD|#zXGEb^(nK8d#8RE;r#ko8$rj%; zu?v}ZwMU!!b-W)gOX=!rw8SkOe1DdbxL0QF$no5lvy#ekT32%SJ>1X5>pm`IiTjE&qwJrSGm>P6 z;7Uv>k$Aaqyt4?m(QWI9Hc@)}hjwY5m8~ix!4T{{rW~p0;`xO^hlLE8x&Gx&byo37 zi;X>}LLRNrXEvK}Yc4GQB)c$Q(qiA!*xyvTPVh%^s}}b|+h^mdEJ0oT*Ha>KUSvmw z7Z_ik3^z$mxsBplZ@u5Qsz=hD#>sITxL~F-(Q*KG=f-)Dwv0>cG01Dwb*EYAXkt?m z4g`!}_pe*xQO0LxKjXl2@KVS7b<487z*Ke;wrvp<^a1KZQFQq2%u)ZByBoy^;tHh5 z&zrt?Dr(!W9m%tsPLGo~YXx3gJ~ztd>_uDCCmnM^J^v&GyyDQM4l`L)R<-_1~TBgvwS zrVZl$gV9FLFTQCnsma1f#rUE!UcAm!@s3g4mXj}sHWl7IE?hY<-}-=uK5tP^%O%Ko^Mni`(3v zgPi;xz7phQ-rAP!_mDCQ(%NLI<#G0zH&XXgC z{T|>(MreT(tZ`{z5<54xy6`et7iI-wJJpWb=ugzky$ zrP9XoZU6JGU<>a5OxEhEUAns@JMxano|;5ijAU(s#nqf7<^2-pg?%>)cT1cF3y$(c z;s*~rx3(=6J*CwA%tQD1HhgS&4d;~o#>L|OZo_XIs`eVLmH)o(Zh+PzSq}AR{iy72 zm;Z6ME+6T@&irpTifE!C#h;#HUUX*sm_Mw~?BUOFst~29`10V4j4`hAwj;KtG4Vd3 z>45w}4HT9c$pAo21s#&*qO#VZ{2dEDP@+GR;ys-9jaQz*VxImkt}%1c+8etZvf_7l zjTz1BN<$s7^H-2XIZ~7UZ`0}u|B6NYMR*`lH~FpCgL-S3_YCNO|Hz2@pmaL{M&^V1 z(P$R^H+mo#|7~|u`&u|V#G5!e@2Teq(;?@HTr$?uW+)Y6By2lLgYj&z_03o|n~ zvY>M2RNrayuC%ZmySX!UXWhz)yx-40EX(O1MP+=^cZB_(|C_kxs0*T7UX=9SYur^{ z^f*X;ytM&*)WuV+MA!!l*oPpWKlkBm2H*UHhTg6x=RUMKtSY}>*cN+iR8t+^K|@I- zIg)(uloQ69X)mR_Z(&Igt7eDM%t!ggsAlLE5 zVz}oo+HAk4an{f3v`*=Y$`x`FSHvlgbthtz+&kon*KoJzUQGDlY_Oqqpsh2NBhLGA zdhck?e0fW+tq&3S0{h+5v;Bhr`Il1XsOEr%9kOK{nNhOWXZEhD`KmL;c@G|q-U_YC z@;?rlhtq?q&LI=yjYpI_=DibrzCy6jUo7sssWhCN8zYVbq|2A`$*hCKu-9_(@?Quu zDo2vi>-3kn-+H%F*+9~tLPBgcko%@v;VO8|t9*9gg;@CgY6%*E5Oy`AdiVFw3c4M6 zX|S?pTrF-pdG0%r_x&@C=MyX@f~ju5!cU&30_$~bekue+&|}E?T}rw1YW=S`8UhjG z{?B`Tc|W0lKS5UcPgSa4t3OMhF<=sItupIN{??27d7A+K=7o>ncA&V>f6{5Rrm{0# z(4DmbS*Cbz`i;lYn6+J`0bJCh~rM(5k6NGZ1^m1|TrRqoPC0+}VrCZm|&QcJ0 znkMGWT>9qgti#MUjo9g%@dc+At4|$i(HWdCcMc#NDoN|=L;sLo_8Py~9waaNNE7#r zYCx!c=~u1b37sT^PiqzKP0NiW{}i;@J!-3G%dJ_WwoMkbJ!3PY@&Td@A6r}))U4as zmJ@v;QI^&ox{%W$(Rv)^0Yvg(9F5xCMXFm=HU2Ab3h;1Cqpl{Ld!+?1G7G?;d@VB3 z-uE{a2`Hli7|fBgk59>vM_c6qe+A*MIS=(_&yrK$9$~MxZ}V%!m;A%ZIka~5p?uo! zBoiH`Pu(uSRZRa-8+v5nOyg_EPTwxt_`{|ut2r}a5&CTNto2WJFh`FHMkTIHqH}Vp z+M0u(hdMqHFVYWVWa?X`AB>>;=Ppl5)Z_k-Lw3s^*z7V(s=$X)3vbB{WFAH56y^) zr|{EfFnv05e9qj&PZAUX=Jlc77GEwV9+|iye{cH6vyBt(RsRBc{f){xt1%1qQo-sv z5kPw}K#`Ahp8djKAY^e{0d3b~dDKLPeG6AR_!C^Sc%SclfN92#o!Y+8;|Ap&c^%TG zp~R|<+_3Nr*Q>eW@O?0_rY9`{W0U)&-+sn4kM8>YP=dt;l)|dL+b_&>I9}S^yJ@Ib zoZoyhciF1!cf2i6-i#bv8ikcI2iBhX-66PD(I%IfJY%YLSqayCuf*BD{Mx3udjSp; zvHsZRR+BIJ+}GJb<(AS*nbqly$&x)1=jWOCK9sL-zLIV|V|qcY?oXhb(!o8!OXu=! zV4;7^90}K$DV<-_uLWFRhOgWjm_B|~OJ)g{W*ioDXRaTms>e=K&$*6V2h8E0Xw1JE zYCC4G!~L*3%>tCpYa9J@kTB%BNiBpDFdHImG?D-=^p)U{MFlU#ZTtU)RvQEDdq+& z1Qgf4)35#kZhdSYd-5kz48W}cGH`22Zr{7V*-u6+0Grlqve%M9q2Hy==t{FV_5?t{ zR|v6VtM6zm24xPA!Iq;lz)1d=s?wN}e2XmGGC_Zw@_E)5i!iqfswaM?%bGJ!gBa?8 zw%W2Vv|!nT!T{>$<~7H5H(o$OwY~NIJ_FfdRI%pp?(&L6eV=7=fb{WPr(9brTDQ!IMI)MA>`s9z%=zHV=HytlrVC9`3|0Un^L^*%|g?GFGyXK>d z9KVlr(-<(W#r42=s>Z9a?LF<|LUVfxjl@;(R(fd~z@7cjw z7bn0Dylw&PUIMx+ATZ*OKYr0&GYjFvJ6-nef?T()_l$FzHc8mv<9e4FT3^Xbog$Nc$ud2sa8v) zApIg!x#}BkeflrDWPA0zV0_`NnYLxo(#tvfF4dL5a{c<3)mZ<(RPi1EQ+GA9>rjrp z_2?PX_2~Q_ih_s`q*gNL7b?Uh$#A!rh1Eu2FMO9Fh_f0@5Wg}XP(qSE$F&!DPwibC zh~S(AyO}fR=D;aDrw)TUrKxu0R=qRE;= z`NR&E##Vl0nHyRjMy6B5kNe07eSAvD|nmS+Oj$^CU5NlDOJc1a>Su4bO;k{Sp#+k~r z{OK#+Z#=~LUG7EAm*F^0A+Mh)vlzfYatJQ{$C1YPs`9TR%{JoKlV9eGWYF1FS)g%F zT2$OUQeXPtMHeiF>P7C&L*3+chIYgfOljfC6=l^3{3O^SABkt%o&GJmf6@0>R??Bd z_m{sfG61T?(f&k}$2ZDQ;s1hpgAoA+g+(UM4}?+!+pdFwej?}GmQ4!`K1S~!)pf7`rIU=8Y3GivJ_b*LTq zW9IK8km5QigA8}-JpIuAUt}q6zD#HiUf)>Z+FY?Q=w1>htGF;})w7my8P&u+ge`gM zL%HiTe($jXAyf!za)!Mlp8BdLuLDmAX4lvKWk=}1>wbVNo{U&!+o8w>4kK^9wYKQ9 zvw%>9U9(F5V#MwqUy1>b;=E0f{Svs{`{e}qpT7kVcRJ=7yY9bP_WCkLrd)o^ zIkLO)D9ZQ3Vz@aWv$4H*g9Jbd4JSP9tnYXHc|)nLS|t=8)gA{w##@H{qyF}sA*{+; zsa(Dn2PgkI$Fghdei{^S4*WbR=ZLj~Rb}qSi^zBO55;N+(XijG>yuz}|1>xFlMi%{ z{Aqd>yp66@=kFN#FGl@Yv}}$3n@j$xx2cT-lZhMq_=t>DQGfY2i|h5~%(^VIFCvU6 zHGc_h7Rb@y|19p<-XN>!cr$bUR&%D$><6?>85|n)1%PP0=&vo0Hq3-Wrka)2mcDPoMi~%s2nH@j1JTRE9{~79RVi zwC8i|l@96pRqQck;nYNDYww-a&n@C?NvE}cN`4~e^iB7DS)%azkcF|^SI+!u7&Ujg ze_7n=iW`|*$3`Q|Z*Ki`Z125!+NadWULhE~;Gq#(E4DD6)iIK_Xj<`g_onvxu2r;S zo$dvKlZRg#HI?m4TfqH%K)vBQc2^4gw_o3p#GS7xtVj9%C=zMCx^0Vh`W44Uw2vooA=HfXny#5etZ_hq9W|I?r^tqnl>z5B^lk3mk zuX)~6yc(JMle-(CMDcECm$AycH-A}x+n(0C$OnU)tq$>mTa~&;mEk~8c0MY|24B)} z(JGnG0MuHFjt%mO-$hdZYHf!DI!G?_q{Zxr^EDUbMOzgXNrb_gdm-p!TK{ z+rVeb%K6(o1e@Vfsr*FI#xsxtBGDSpY-!0QrW?L=fB1vFDHy^hao2wHo-fvRczEoK zJNR$s9A7P&6@Z1kO|Zb+-a0!hS);)e4=PWl4^l*{E@qb;Cb#uPd|w>3oV=hh@j!oDFn|yaPmCK zzKz^e<*`^!9*XdWHvRMihD+mvZ2xkXR1aAYe*g#FmLNkvx(LP9%d?kW+pikqj!jvi zzF^trgP|`yaQgrsk5du)k4>M69)G><(bwTlpWY`YS|miWGAhXHSXk+RJ7|LSfo2L_ zBsQ_}{$FKv3NmFp7wj*_tOP03&oN*sC)pxhn{@0tr3NdPhMj~pn>j9h7F0f@1$n+b zcE|NBbpS=az73Zhi#@P<1LW8;$Uf1AOZM2UJvc>68ycG(3HfsWSEZyQ9u`u3p0haW z--T)>3gO*fKX5;O(fshXIt;sMu%z!Tcj`jXg|Ms`BH3$vutopJokVW$k%4WGDkeXh z=?kToM*5rQd^o?Uw@xdo;|ikj{Hor%eg$0JbLG~@_xAijI_>j~|8hW++H+idW9s)+ zn9=C&cbfj?rv+l{{lRKGV^Pz#H4RyhvR~{|jp>iME>zFX)=M@%^Lf%gxUx?9JZ; zKs~W0!mcUFJO8WX?su6f6}^fp2YjvllLhRC_u|`|ZB9c5$UNy4;?mBIA6aDsxg#eU zqjLA(D~g)nnux0uH4otcRlKX1Bc=~WL!F0U0%an26{deW`M&%$V6JzI|I!^D-ZgVA z=BPwjTctQU_T+x*D_$B4=x5H<#G==M!#`GyUS4nT<4sY|C2iGo&T4K>k%W?rt6)?& zGK^DJe7##T`z#pBMU9dJDVcmsxP0x;_P}KnMsAUi!$j#eL`gQ(9CsrzAR@v_cf>w=k<();t0G~kFmZxa@_MrrfmS-+>w(nlw( ziSs+Zo8PMCxn5<1zlNwpGEy?~<_4YG!=z&swwN|9?%S!fMv}aPrIctv8dc2z7HHKWNfzp*9enSl)SKU8ItN3}JUn2ko@DU7JGl|pv||UmJR4?s z@~c=6jwDkb6%XSM?b6N?97{3&kkY@}v=7sFM)^nklsRc}?mM2oca`e&PTYO^wB3oO z(=(>_OIn`qkQcdCQ1R9XAkV$5p?_iV(vSDqTJRk6;T^eNg@Iw zNkFoQh{Pu6AOa#;CFh(&3xZ^toS~7N1O+4qQIHIhl`I(~=Z2x zYKkffPjQ+*?EQuHt+jUc_)%Hw+)lF9FSN$%NJ1IV+`ZAhAqf)By?*e*Z|X<&r_G23 zT{*|uxciFW7Y+N`??R6?*2?iJ8o7!7d!(c+yE|VTI_LBsP2L5wUt}6;p8mnF-DtX| z9OWq|;(>^w<2h`cBAs)r?eIZQL|&<;JMUUtECExQY^)!^gjD zk;9v+8b2F}p2h?axvR;j^xeDjk`w`DUt{G!|9Ca=yEFdaaX?Q#HL1laQr)!-R%SJt ztKX>J_Re2VVT~U~k^4VuOg;NO}zr{I#osa{XEkQnMG7wXEol z>neVb9Na(l>=>BL6$(gwWen)%x*2u#@qgh(Uhu#1B6u4j2kmx4Tr*yjEEl7{*c|N_s!H)fQ>ssAXvraysjP(Bn?*to!t||)%(7n z;?y?zC=4Xm9+KQk0z?NoSXBR)t_C&K$KG)TR1n-@qVl8GQ@J#&KG%*Ev~mB(E^kGZ zwXB&w7P^*}@`r$_U~Tr%`s9gYO}$I!h$=|%pdA67U@0Lemx34wVW`@Co2>vxPRyfM zQtuWBlp^rYlalH}FMPYb!XINtN|Qe0AI$CS7)nK+AuSUUWv0HVNe_Fd_}iCx)-bx) zTl87+^FA5b2Yn(9^sv?XoFJ$f4@^NZ;~l+n^bQlOM8)9VpK-YLoU-6rr!%wA6z3hC z{w3m@a1>X*(>{8QU)~(SHUrlbxI?afo|nKn1nBn@V=joM@1IstEGNVf>*}Wvy#zXD z_+jkiEpPBor*h<7T8WFafM7zEYT(jtFMC`X!kg^KAi&b%(oIdaCGC^#bSziMVCcG3 zwg!qKkeY&^8x3U-f-^>~TXj7kmK8rTmmQC$7+W~y=Xz)199CK16N{}R2T`7K^mD93?@km_4*veg7{BZOqk2hoMnjT>bHrUL;rqJM zQIJb}sp{L+sV;}3P+dX3eEQf4{>huLs2VRbAH$uKOnK_A!L?3xFq4juHR#7ws3!LB zlftJzf^B*()4{B=q_8A`!<#$(H9Kz@Rp8@@GuAnow zU7edVG}x1x*HKNHj&O!xMp>nVJbvS>gCf|kRBHfoPv8oB*vmq9bqc$jwe?TmKOs%kVx)pUu{c|i(ee_h zYU#_;k9v9mU18i+N@p>H8U|in=Gyftr?CO($tpOrXGNjfaN8wYAMq)5v3jGCI{N3x z6w5#lzxwd=6N9it$A%_x<@nY#lp?%(LC3!0D)}xfWs%c<`V0eaXk*aC2bKbd)Yu!j zh@k;XOf*y7vQwv@)%ZiOC0S#^=^Tnh>T^6K#&Ok^ih+uxWPY&taAyHA6;Z!G2`z}s zqE=m8I?J<$v&ZFLiAqitu5+D^?%&3&tE7r+T`lhpvcXPz9~d?t7>?)Jd}2R0Pm2yk zO}afeIW{mX>$Sd3rF-Bu^TWaL%hJ2B4NtC@cR<~Mts%yn--6ZN+a!Cyf>0D2CyL)C zd_Q`^{Yzt_^1Q%nkv3cky6^L39h1i{Y1ea#9=bD4USrq$ESTRDC0y9@@zXbT!KZD5 z?xQoEV;v4a;~SZq$_&)NQsu+ggqyhZC*jIEy<5du)S~`99%9m7S7`Exzm=!(_@T#e zs3}_8M(2av1p6%If+t3J;Rf>P(eH;k-@-rlaZ0DUHFTxa-#?m=xJd3}vi50sb!&_a zdXOk1STnnh=oI$wll(W^IH58dc2EUE7coa^H{O1+{Cf*9a632Zcw zt^IC$a}Xj?P>l~`lTLZep=I*ByO9RpSSd*2U0LplNSf=BOX-Wg)Qm{6Hw_IM@SUqd z_D^n@?V>_BCHv$AtZK7U9{ln(4JTJ^pcE=GNqlVl{BGc~bR)M(X(ItLb=HzFkK(in zlS8sC>%~6MFyifGs4vZ7-TSsx_%u17Ta@M&judW^6VksF{suD0w$^!5UxA5_QcVX^ zD$sed)w1Z}XvN)|$k$ji(qP{ihHnT8MU|C!sj;O+|HU|-D`v;*YA!!MPe}H@#LaRV z8KYSlH-?ql9)y}r#j}=F=?G(jMu<quwFk$% z0v%?l4fPs)z1J!yhaMN!$NkJKwp$oXv`1k)rdj%=9ks74^eQkA_+kKmWzY_^j>QK_ zjwSX#>E|YFWeI-POb8?w>gzr-id*#@Y;>~8ECM4$Tu~9po1|(tb)gy!{L`4WpxjV- zwySGTH-D}h=GcZ38u}5dUT7=c**UT(c|-~;m+I|}XAAec!>%I)YEB95u_@<)y|4{N zIP?=ypMgXsmGe4h?Zzi~0-&WYC?mX2+>6YlIqDlc-R`a=)Q{?pfZKC^o6K*NVfp%!=wDiGV9X5}0))&4uP4yv}ifl&5XAzV;)sp4;$d{#n4FCs8rM*3=HTe`0c^ z9Ed5)kPd|Zg_z{mzZp)3HA9Sm14O6SEoTi1oMLYtlr~d`18ZEY@l*rvcEbiT$xO3Vc+M*`T9Xq6s7*!+pHa>3`alU+ zbKqkZ^pf<&^b%@UTZ7f{LJl}kgS&!LXPfgjc&_kS+>Jo8%Yw?<(x;W<>U;3I`3;!T zsIwD!NMOQ&s6=K2rg>Za*4-gYUt6Lg?<5VV?=pJ2n-PbP1>{;KpMSha2N+V5MMQQA z=1FJy|K-wY{?9)&*x*(~_3f?QC@aqx&}m53hhAC``P1q@qa8vayX9fszer!nLHuMt z??nMFf6mDcKdE;tndX93{O1zbUY@5}r`4!e%A%aoi>6f!q2kG?Yjkgi-B+ph#{DVP zhaJ-N`PyDmVH6B3Xj4NtC=|@qbm~4{B=wklHUWy1pSwHB?H5(Qf#&PPw@BwBomMME zkmA~$z;>%7O12Q0iPIj7af?PB2er2SV2*#dveJC2FB}a+1?77EM5%{XA2dl*=zf`r zgt9!t-p~}<<~?PMBw%f~(r2y;MLG|xbk80LoZc?F zLWs}ZzSi69g+Q&aoVk-n^AHrr8B1xxUL(sypnAY@_)|ToJ)lRM0;&@aOsAPz$Uv*I zq&!K`xf|i!Os&rY>u*NHZq!kdrVJm6ptNSTiFc=H9;=n=Mvj%0LxIuiCp5|5&L<_O)YiQ zJkkl)$&S>y{vO>UE;HSnmYNCOPIR|mZf^p=z>$rBy(wr)HM5=S*wJ^Lj{8lz4&WSK z_f^4wXG{9PZ6vJB@W%%d3dovTj;ow{-B|ohr*M~*2RNZhc@qsBD7f3JZ_6&uE9$iq z4VE61qV0~ij`#a6cfvPnID>JM+<&g#Q|!+2B5#sLjDVWrhnb~5Mhm9$ixt!rnb(GY z_p!5q+Fu!C0vvkMc}_#>u-+F4WH1!WUz5n|(r0HhF8Uagn_x$T^k77|CYa_ke|MVh zC?T~HxOeOfA~y;)%ui?F$rv%x=P!HT1au_ZypK?Qdxuv1(%RU5xNNN%B^7}?&Fj;U z6(+W_FWF5^0OLx?cm#+{Bi{!7@7!o)xxpL4NBDRq*`otckDPC{M?4^Y(zjTUNY){x zNarA4LJaB!)v>NPD=A9-IHM% z8jh)TbgK*oTSOsp^uUE;IH|bB(yxFk)o79%8l(4C7fSYTnDxgmjuU+Y$2&<7P22Ec z2+3U6)dY>udNV+SdJ3qBmKJK`JI;GpZdl_=iG8L&k0Jmg+16S77BxbMKX|rJ*ffhB zrZwhEFW35rPyr;MN}Fn{HB9|3PIn5cO~ZR0pSKT#Wom`G?|~O1gGJKBlG_k;x{;q~ zp4ZRV<6{ooRqQG$XW#;?R6&rKFtSWqaNpR*Y+_Sj*iR%MOguS1 zxv|vpp$bZK@SSHJkFN}u=U;Xpg*i`oxwy@ClkQzGOg%(+oamyFCyj$iq5=W1-)p4X zm5mtPVVy$wYIUx*`AiocQ+e5qUJ)7+fDd8w&r9H7wCp8Eh1wK9=zMv>C4ORmT)U^y zv7)PfW!rQ$P_<{X>~$cU$G%yj_oM`$LxaOnd7 z1CySVxa8YB<}s(kt8)a{;T7Pm%>I%z=kX7|#j6LE{-z|T|4iTOn#$G%>?l2UYH7pH z$ExqzPDZO1o(YEoFXh+M%Yh%hAy5NzT4mCrITv{G3|y~GTDfj;V}>+2%v#_2((!M7 z%*{`)8(%EkCjT(jqcVY5Yd}f%h3o^-ww99b;Q%qw1wk-O62+plgQ%^Y9FQL-y$+}n z1<`7Wur<=YR}@1Z0c;W4aQv-Fy3JW&jo7Qiw@>3}gE`se(;CaH%ajE*pVMKa{l<&{ zWuIh8<9JR3MXge&PC8;ftyQ<$dGlj4?NF?KlKXF z3iQGDSB6-%c*8Qo`?!}icgMxU$r+Ue(K6+^teo}fL_ZBzEiBCty%N6px=|>a_Tqza zr^_>N#7LB8jmSBbkNDp;OPRqU9O@MX3}h>%Zp1=SzXbKp4X~R_xJqx~ID&Z~hyl~O z7L4dyD$RjpWD4X=xhdWiOAJ#td9=Jr==^1m`{{qu1zzFBqAzz91d*N688;r1LPH~V zXYd>0e&JI>JC3iCV(Ve49!J$C?X=?ICn6C3KOjn`Ow1v_b9uB^PdV@on7r+}Nfd?* zJv5L=z*FV0UiFyRdlUgmgAXX%b@d0^<=pddPGL^4pyO_Dc7L6-IKCd*On&0&mb|8V zkRSOR0LP1cJZgf$A+q~OM|RTSZ;CZfhNoU+%0vt(b8ndp^xDLk$5#a!ty+z#OVZK7 zuDHI`q~ir!y!xFH81H_L1XKa~dqkorS>qwOT~UJHI#InJJT+o93zW_O^gRan)hnTbbC3-l{_qYLk)Mr3aZa<5(y_ zX1a?wKp8NE7SgD8dV z7C+38Kvx}8(9=HogSC%)y;tw17Rc_%qBo<62>MVB@Sn^WPJxSESuYZ|?A}RadaS}_ z+n@T})q}O&(6@f}`DfN+Nld^1^vd@4y=X>at{JM5)h+%2Dx?9v;68KI{tVEj@U2oj z@;ci4-S@I6@z8**T1o!coC#=z3WaudNw!y5VZn6X-i{NN$ir4B(MhFla+{-ACmlM= zPHn780{tW3pyR%k@R*dDGsAXk?{OR31U-1#LiAOS0-FQv8`JXEM9T z-V_(h-0BfnJq#^X8GvR-j*WeF=jWiblVJgdc-;ZsBU!V zrlwyveUDJK`Jke9ES(u%T)$1sw{l35X_{|LBnK$*0^3Y_JFN=|YHwuR5|W^@JaJgX z60$t3mgtuy_HCT!yeEGHYYupSkPS@xw_1tRM81Mp5EgVe+rwf8CO#%8*HI|8qyb-; zjUg89M?e&a^Tv4vI2HJ_Oft*Clqqc*M!2>()VphJs|QiCD-zik)3k$F7{g?1wf3eA zY&5H1NdiYB=XSXjHe;8s{3k{ELK$fQ@yT~3Aqz{ABy5o^FrI;zmLC{63{C-sg~Q$287!vdPbZOJ?FNR~W}~A4hRDezjt+IRISq zm91RvXM(y{Psj0uV26(YEc>B$gXXm~oQiH@a!9$w>{WRQ@#X#4*juxmSn7nr@C#1D zJnTHerIsFDRVId74kc9x1e)T8O3gQ09Nc~XD(xe^4{G(T<~Gd} zze5AM{3yB{PehP>4IrrG;%>5{0LNkJ5%%NopKSh2B?Zs0$dv*|@-#s)cZ@v03}(uJ zarPjmU{GqSP%g3XW-`NC;Z5UpI~nX!`sW(R#K9yK3#?I0Gz7a5X?S4CAX7LUz;44{sRmV&#CDYQ$2(jw6ZfF^wz||!6Dy~6^x$VWq&;NLtY509Q)AwA+;Xooe z5Z2GO4xmAWh5b5&l_U`1#A0c4+l*}U=Qj(VCS?yNYgJ8~16p{37I)s*FRx(esLxJ8 z;=tSx)Suz#76RB-uC9S^q14L9Otw1{^7F5SDh{A_{>E7g$|MGn`|7mH#)ZI*5m>}Y zCnyX7Hrp>?J}Od)cSs1M>s#D5Ymz)_wt53Dr;-ls_zj**8v(o^5sYf!T?TY=G2wP7 z13E3zO09)zMnk=v!sD&Tb6lWkUZFd>6{5OX%{?W3`q#y2u+E`axSiAi%W(!Z>8NM+ zgrK*&*1({%f#Y!jVtI@RMv>85$l3W({A>R5K*v!a^gVRBf2pZzpgYmDC@^tG=ZsKd-&0`nv-e-xH3mN5#g! zIYHObUymO`H#{9aQG+H5%pUi->3h%fkUy9SU7GToO8M%*S<-Dk4xF+$K-&3NT#GR$Vm zZQfl0`?iQ#iwj}Cy=X>B=#`Lq6^dMd z4VOpiT@gjG;Nl!4} zdQ%uVg)!i2i}aYu_xA3>n3&c&sXGh02J;V9nTQ~Osig4_Qwj7gE9{QP_OL{7`4Nyg zJ6VDt0uwX%YvsnL*j{X4jv!EYjr>h69SAVR2>L@}*fSy@J&5va##54clkVShF;GsU z8}1Y1e4?G+0Z+m7HUOciy(P1h<-4x_p??*Lygj-Jo1u$9AAoTqF)llZ(#CV!YiFtl zER|t=iVRdSk8nM8`YkSmyx}KVYAykb8^5>xqj)2Iz;NDdIQNT7#*BYaqZ1LcJ}bm+ z@<4l-uIr4^ayqXm0GuCez9nzyv0PsLSdR%xB*MA=2O*~pAoHgs%%k*C;#hVvXmOjs z14cd00aOyyF2kXKe;I{0$By=ErrKhr3 znS!~_mf{tpNw)kB@ z*z;$=O@SD06^_ARA>$qgslfQKVH;Ca+0dnTIA9va|4nVc?~tC=;BkjfY9mdM9U2WYyS(^Yi&o1AlQyZ(x!S_cO~j2q=3=1+&^aI$ z2!*sEJoN;P{Y8Fa9Y{c$C#rkBWW&dS zsDyAAwoN=Lqhttok}BBN z`_j&|;~`41FU!n_t5XazwOeOOB5ZtJ-@pguCnZj*9$0t5Z;a`tJ4@7XYgV@L=hY?B z6;R|@Sq2R-6h*L=-@-o+0Uh8)MDp{XB&fRW%YDds46dhc|H(!ud7;ARN_`%QbPc_@ z*|(9`pBYWP*Z_$E2`JX;!pR@#L2u7}8qrhT2$jWYL~t57m(SD9$XF4!b(Vxe27e>a zvc}zw@555JWOMbei1gTr2?2}}j1bi!b6&ES-Gl&zey`jkQ5hK7 z8UMaf$qU{eBBL(szY$+TptrF_2*)z`?aAD4CEJW$C`~*z9otV=DLfU1TW?X{0yPal z*-jnIamt)s;0|X=bYq?Id3^=gk94pkekh1xm`ApoNhBa{I$UmBK0H)cdXab&%LBd+ z_?od7)N;VStdV=&hG0C*M-He@8QMV{!vLC6{Eoo==V1W=|P%3D41KUAeu-P^M2>Us4yl+1e=HY>*nRF}3;EbdHG&`GN z=`St-mOMBDh=^kJfY!ly6HLNQ*L&P(ra@ua3UbdGLG~Rn$V_>0^E!lioTsqhkvo(r zK;#PeSts)zpdON*idMj9HU38;BD}mLXHskqe%#qC1MvgJDu|+S$83OkRp})*MRgG& zUio1Ri3MI}7noDwfb_a}HSwL-+2rncgFsn~<~i6JO-U7wmx0A_s;v1Z+Gd1SqQKq< z>=u=*$NR%KIOS|1a%?V5G#q|C@8b?$Zhr1Wt(`fL7Kx_vTmwsQ^CAPt<9~?7HV`x3 zzZg{i^Yi+@`ivs>{q^sG%Q%Z<|46aUIBWm5s=z3^(+ct3MY?J6JNv4$FqVH_Ngw?=1e5V!XAe!EAx&>E$pQPNzVFo|jhGk&G;HjKWWR%SN z9WG#W?q9(6YM1|JbpBaJm7E9hL6L-zAaJuX!)yndfQ)5*?AIW0ML59vW#!JPPUeq| zHE&?3J>VSD+q6a!#%E93SU{A1UmuPuNqw?eG#m3lYlud71Z3tpl)0&&o zer}bg37|8hfe$?B@@hF63E$? z)II-uPizp?^#9Wn1InW0%hh1-6$`LR9i4GI|LTwcb=ZyM*}}O~x_ShqBsj;TD3QP) zyB>a;je5TBbV;6e?E*R~KoQ8NSJ`Rp^!Rp{Fz+^a${mSCrIdiC3!vs#vuDyGl4i}v z635tAj1}h$HE1wE-TvyNgxGgPKcBs<+1-Ns5S%^0HCN^IaM1cAwiQVMF7KP*YzV*; z1xWZS6*`!hgGDTI_1{IKf(w|ELb1^$1&@FYq9-5d2|4!$5vFnXJjNQ0S!wW zAj&vX+hW(P=H#t!V(E-vH<`aO4L>`@LxxtQn_35)G5`rXElXnB5Z}jBcSJq|u`-;J zN$QN2F9uE*ASp27BRf6m0suV?lfCV<|0Cu7tmH`luQ?IuwN8v)-Tg}((CKyaig5gx z@Vkw0-`;oHKh`||Qe!QMu7d#fyC*mjeKynktDy(GYtk>454<`f1=2YwBAD+(iv@8k z&DhX6=@Iqx_5|bOJ3ByBh0UZ}+bmpoxL>eRggBv2Pm2DA4$IWd1F2Ds!$;11v{;!D zhxd%ZRWn|2)Q5EK85hQR>Q34lk$*esErpr>^@Ll11+Er|eN?wXto2E^4FPW- zjw?n8y91b^e3sMe*H~0dbXYGC@Ym7HVTTsjxdgTaGfe{nG5WE!a(QWo?fZWMUV12& zDJoU?feBO{B!6nVLxNs08W|jQGML(7qV18aeIMx#;8pY+-IT01&agA3u=y0DHz9u5GFuxgTq(0-|G@(%-%2X#)A@6+AK8Vp3ev{1>`x zf2}g~BmJA}0xP)W0$ZpyKNjNmwUd`r{NPyRpN-G^kh$*wwD@#K>!ZIh^48kB;z%%N zkcfot>+qxJPGxSL&W)eGp&i@LJ0TYdp z!%6Rk#KTOBaKPAXD}0!(06m)8YRit806cd?aGruCaHXzPArd&%_kHPgy!N+v^j~XU zHC|W)*!N2GY=X6gnnhDAzqF}q(COj#$_l;Btq07MQ=!7~$c<;f zZS|Vs2p85BI$?={MDs>zNYp-QsZ%HH5m=ZunRL!FqhvG6MBX_T5zeY-!g1`%-mE+i zwx<%xj1(|MH5y%QW$CFpv;0nu6BnfbMyjjRjDXf{9^Y~J`Q<6=R;!+L3&MkJ>gU&+ z!og~@lV=&&8B{5SROW&g&O>4nPj@;HF&R1Q?qBjjLDcxRnXn$ee1FY7Q0s}g$x>)T zBG}*+V3@=BsWU5{;k`K5G76QHcuM>JoC-c%QB}mNW$z z#IKkxe!xx{k2XG5VwndjC@v!ToXqFCPaEzX-tN~AUrF`%?FCTQ9W0dfr|3gVHR+zI zez9X%rcTPQ&mn_;A`oETs9+?$>1aV9S#(_4c%q0#A~4mnK&-$o)rR}$z#2Uf_^C(2 ze9ylWoS>COKLS$LLSXt}=W-=FV-L*RBncAlWejQPfAxyG5{_yL&BxB<=CE)i{Jg%+ zF|K5eml=OL)wKosnhptPDiA>eo4^b?^1JHZ=p$!5YMnC_l6XCoofJ4N02xRIYVB;0 ztUqX9bioJsML@BAH2NO+m{N@8MlFo=Lmw6O{%;dGD_oy54(#eek-#LA=jp zsDNa}$4LRPm_qNF~Q0Ils?w zZ4bjx$$s=M!CmFA;ISei1cqwvjse<^Uj^O37%>bviQ1vGA5$D@M@b&EEofV@MzU9fSq2XGAdcATlf-?`YdBEE;$WS%l`rQF zY2zg$IGf*805xdY5n zrTKMxi>XQBIt3;1NFlz72Gn-ZiX~7|X#+#DM(KgSMQ5iS^*>AWwB>6-%wHf{64R`8 zLB!ELA-af|B@&jEP}BJ+Nq(|HKG47!&3Qs|bOp#bCX{r0H$Fx2B_{B*KY8(I;IF^jocg92|fYu6O7K zueN-dAA4v}k~z~`AF{FfQk`0|Kz@NycjEetvc^`tvE6A?pAvc6)MJI>*n z3sRionchvC)O(n6v@|WmCkGe3iQ1SyXgm({oZBdD*KF0FmaqWqs?=}QSLFcbN2~|S z2x87fus3=vEayamKtVkbZ7~OzU3ABxlQ

  • y029mJtMR@qrKiezrU6q=)!_a!?<0*bkv`kz<3{ensHWQU_0>9vn;TmUWBDyS(^ zQpuIU1n(}FYRYV`WW zOJDYxm@ytD)DO0lCPWGZoT!z!M?Xe0;%>>T)AWqxx%{o_}lVX@Kv z$k(^_rz_Ve=Na>5L!iZy5aKJM%dsqatFSX5FhscZIu!%;iFB5-r^TUqd>HBB_FAAw zAk;^|e|8It{@&Kjo_(p)AaELqKVz`}iQm=7^#;y6?3AFu=pQ_EPA$4gjd!yH_o z`W7n;5bIJ!2#E3|6={HiNfyXSu|aeaw}$->Uhzjshq40r$1^a=qRKUuoDSC}>)3!D zgx(g|71-{BdlwCDF1esO@JQYW61CCcxM@Y1(E#07jn_pZrRyNsf~=v+ls-nb0l{67 z1p@=2wX}nL-4pY}N~IVh8=>R_=Y&Q^+)2%9u}QZBD&%i{G+kyRZ~O8fs1|1*hKmwH zu-RI?g2UvEh!Ai*C=8kaqaNf_TXRU2UjL4Hd)UPZc>{@=Gj)*`}rei)i&>gMd=Xja08LY*ygH&0RUIj|F|a5Z|CM$Vg-8& zp?)GVxH_E6flyjaAxzn{29n#@p8zuMy>rcesLPCEnrbL()CKcKB18b{it%PATC3}P z5BQeM{yYFi16$SY;eQdy{gwZwqrz4HGF2JHjRG7Dff<5^D6CQ%SWr~H`8T+b4R*Yd z(Faw>c)qNMw_!z|L+~avu=oY|q5r$$A+baC_g%V6FKrsr$q{HT>}P1=23F& zpvX@;+^GQPL{-L?8vW#zA65Lxeq$efiXOTH>G%)WxyMwv{eX|x%KOJs;?tx*%GIgy6QVSnfLgUfr@i5}Rp>r8 zwYaPcsAs=v(TC;d9EPwU@9!5zJrE!F(}8Gyd@E>BA7hWkIu}Hn2;kDh$Ssj8K9@IY zwe?_LZfb2m_rMrLuE6`$WQGqYbzOYQDbGeEz!yZ-hIYI4tbGEmLjWLKWII%Mvs7tK z1!J$i6>F26X#hkf=Q;`p`}U@C8@}B?>z&pbp@MimFTgOAV7OdY=$7}8I_i`D?XBE> zj)*J&<;nkv=>xmn>C@b>$23or!43X4JE&6*)1OyNKqiAbX@d6uZTWGaE&d;|AF#|7 zuj+1cZ58_Zl<8onkdJY3ONoF5!6Us;pymVvOy6EbO9`M95V$Yk2OOQMvKE1(#}=z+ zdNOEFYh)3h3T43WoK82-;U=9v!C%*aQP(T*tFy#zfIW$|fGP&RtRp*Qa~o8RkHG8( z!x8bf5!UH=3Xnt27IRfrfMNG`%Ed+&IQvQ!Ni%|9YhtYntE0EuiRqD6v8{A?+x1=e zPXNk2IS62)C1eB33_yy7m%o@0DmXM>?yY(erQ^7sh#fCx zAg)t*hFVq*a8Pw8?!6Qm!Sc^{I8##-Wrsh_%!1)IL)(rMJt*aBG*foOXgp8x5d(9y z9|p%(404w!Z;XM8^WIyL2~>gZmh{Cayj;XxGF>j^N61y%5hAH$WvUZn@H4ES&&FpM(l9)@2&es%^DN z_V(ufi@Ih6GNN<1qb!O0jM&qDw3B{KE0%R1yxG^=o}0?hN&wAnoh+$GH_lanQ_yT~ zdrCN7^5CGtY|C>pZa+UOFCWara7$zcrnw#AVOc`W5)6rLbh;zqYW?+yGftf3vD;ze zhQq?I9Z9hHn7ThK&;b*bG{7%7N%>nv|8L-RxI%uoHQz#N*U6#sm-Plk%E_)D4J+| zeF-T}d|scY@bj}6(2*vjcmh$pQFo4rL4s=~kAy3bg1C?H&4mnKIz9V`NfNldhF>s) z4?gMEd+3|5IsLRyuRnHM;Oo~_FI;(VvzKzB}^_OK_<6XkFufY*Yfcn)ZUxk zO2(woP;))+rdetM%w07u@@GrsQBf~i@4$Rhyoak5aTD5)W`f<7(9M#Mj%Vp$5l~r4 zF8zjRx^9OEsJ{Vln;_n}ROz)9Z~@1fSmsE+COKw8+o|6!+o%Oe#m_@@du5UL`tq3J z1xNGY8m2pYcl)w+YZtTp&GS^NP^oI>stx1!7-4EnChWp*!wRC^%2phhLQw`uDX8{% z4fk>Cq3+!|xYFW-NT|*Fc%;C`S+bY@{nOj?@F;;5;Mfo4XHY7U&UR(qN8|LiQ6Eem zvlS(jm%Q2z7;DG~*SFRVPP#XHkrwor+qs5yG%(*frE>q*Lby@rC~E?~XHSDgqU^Hq z@s$(!D-%t((NbH1%qR`-s$c)i{JIutPjl(g^(`yH>SoF}94`ZA<7dj-$Csd)nU zxEb35xm4#qS!pMy4sRh)cyzGABSmF&-hkjrrUiPgllo-bGjYCg>nif=6a-=zaIO-# zeUu~sx1ASKucM(1j{)S%7HE3${21gel40VJb5ZVNpU1Q2i(9e;xV5qHqPZw9DtEnm8lVO^uclp`pYU#$jHs;=nPceCOu~ zwp#_YO!3Z3Lz=-Q5&5x|o%4A-BbRN;ZeFzPBWEc1!CW(%GJjh&dDrS$wi4PDFC&f1?#MIILsj=@64ZSiO<6VAt9B)p80zm` zV#BK1IN%hlW<>|iUc*@F=cYL4?5^|5JZd}?TmQ!G^(Ow+;IE9H?XC5Ri}P^z3QPqj z#`C1oD=fcJvjWg*TzqA-zc3&{-4Rt@w#U}raAkvRo9XEBLPhpc;)4u6VCzv{64m#m zoq8ueD30($kjQQQeyf?US}gR0Mmlc&CVkMX-gK>HsBKlbxtD|yNv1~lYm8sC)$<5w z#hR((?|0MO+e|g4EJDN=5!ls!g@^_n0d4zJwRJ-zkPJfju3raf+oA8?Df{_pRtk&S zsc)bs?`!O@GOhSYMN#W=o9ut7r5AWdB&ov_E&S$fh@9+ezlQ)`A@Fh($!{cd=$bmEns7udT>jfe!ixO zKB?=ZSRLN^)ndIgjw&w~WbL3A?(^()oq zbuumsGV0D{X3Tp9t1+s@AR-0@_mQhnM_l4YOL;+)%L$%8-z{VW&mJi+xcVB2a8`S7 z$}HO(ah5!OAIIchJjYR)hN8^8@`=-hHF_m;KCD4qwnTN}hvN#l$>Np6xZ2oun68U3 zLA_FJ$82M)?0apl#D}wSDY&Y<56y&!VxUY1hXrgY0^P|QJYJXGmt_Jz@z;%4Yes23Ra#nA!>=h)2HliHG z?93XiuXfMwT}j^^KIek2G+{k8_t*wGt#;x@8WkS<-KrIr6}ffh*|(j3W)4Cx)mG)K z{iTAk&+~@HAtr~Ggv8q;P;l9T1Pr-58lNJkW0wyadGXqSy+QJLM^@SfnIQUOXDX`i zLD6?J28O0^Av7-ENs&Xcj;3{KLptZvh${EhFzLCG-ymDs3I?)O>| z*Vj|F(NzupU4Dc~y=UWle$ez2XrrCX6yxk~i|P@ft-QRLbopB6URnGh+qr4sjHgv7 z>e$g3PTt^lYNwO(o77*WhT7{i_o_*x&|Hcj5_Yl*t;1K0-M6J>nFm;_r^c(r)5bms zyIgc3L}t!~6F*0e#QxsPyTRF_7sRYPT|K%j-7>VD4UJ<6p_rRfRgOnru*g0c5%3G= zxnvvvc_r56@Ma?-a5Z}9V4QiP7_G;BZ^C`wfh^_?YwolI7qU!S3s&0Q6c}jJeq%fg z&Q2fCB!YUY_O|CQE&wgqsq<4LS|XqMaAZ5Eb)UO_8LaM>2!VPr!$`_g4tq$2j5_5x z-OcpSBoC1-QTRhMeN1Lovb~W0G5WzvZZ`nzvvA+!8!kDQad2IQl||VAKROyJItO6Jgu8~ znVhW>32j4U&BSs}$wn^l`9la{ZHOqFOFS?z-9OKZcb6G<;qTo%?}AGa zER#hc{DlZ)OF-j7xZLq}XV?cO*kD=k#D4Y)F*CV(@q#iTQnh#iUQC`nZ;gzQ^(;O|!4D>Uv#h%t3Uh*+bAf*pnmH71!S+#f-~xp3U% z0$!lSW?_U?t+B3{GORJ0XM~dZo!bgPiK21c3{3H{d50P14BORkn`=_q22NQQ)7e#YLJ&61Cp&waE!RwM`3GqJ=T;;~mlSABl5WjD2u8|IqMiV2Iq zoNT;UV{hXcYamKx`Q?%3zh)SYYYJ1-*|(gk^2$8xJX}PPnHLi=aa=AMK+8&H&LN{)bPakyJY&Xb zqn;zMfq;*crs?2ZM)v0#KY5?Bo2~ldPQ+`BTKGzVGEu&EbLn=_gJP7$zI?jBJS>j% zb{F?WEMC#XnDyccm={dq&MEIU$&M=SDv-wpl#PrI5md7>Qk z83BV=C60dFppPwL2(Dt;8xL65XO7qHD~rnSYgGZadNx0OjiOMw}MV$s4^u4m*F)EPp+$HAKaPp z)5z}ljVzg+6fqDV=9Jrc-y}g%zh3_d-IEeWj`eaf8}{7Ja_?)Rs(k5iXRwsf6vr~| zM`wvklBy+ZLP9ZS%a`y^+M=*;#rDHl7kbt8ns{bVFNuM%tc z7rU1%y>mSEs`3ejJlV;mv&8=EDVDX*@F*Y}${enfbIIox9xgHpeb|EydWe|HsZsLT z&|9OIa9VHM6@_9Z6{X}w(YIb^5P`|0&kqO!%Uu1#i|2`mof5nyg})7t!^JdiKke>kUnu}Lil-;B49+epFzry1B; zF=YCWHFSYvnZ!Ob;(#45{4TN(DSi~M_>S;cORdPRgUPu|FdYKKk|Y$tpot7=r?x&0 zKDzd9+ImoeoD*_>h5(cec-!B;-^2+g%#%QyKD^=Wd{>4}i*cKYF5;>x(fK)L$sa|( z{lNaZOFHO@R0@9B%PfI?jWM3wdC0HS*CAE1G@&Rn4j+oS{$io3lg{oZEVY37(?ORZ z8Vc4|Fp>4!w}6R|fcjNYlJ_;CJUK7ufgT~aevrFJ=EB~w1Y#VHnlN6NQ(Zq|b>m-3s(R1=NPV6WnU5~cGpJCTYjF+*)xG08A zlucS>VXb4A(C)%T7uk4L5C5cQU%mmu$u9ot0vDJ~3aiI{v_pflXdc&c${n0G#O~@v zZh(Gd(7pz@CqW_`igP{$(o73O5idnv){s50FlVFt_LK$7T*{tXBD;8AqrV~MF!ABS zePt&@?;pU14fB(^^sieCX`z_j6t4@2d{atW^HGmlT6(lr zMePm3m-I#81NjyIYo9!#-o-=VSa zt`Ku>Xb|F^)JLP<38FsN+xI3p*@JS0*X`|*rcQ1!n4K%2ZO1g`VY*iifPLhDSScdt z$EAJD&%q+Om^{6CLni_%x2-_VtHY>}ti9_OZq98f!g*TeII4V+mcK(vr!~1mB7v>1 z+Q}I_%kxw)UNiAZaglG1+agA{su9P>@lnu~L~*Im9lEF4G5PQ#7j%1ep7>2{QOlnb z9M<|T0f1mTpz#{mL);+j`O-0CE%+pp7H`mfaG$5@e{TXU{56NzWG;Wspn-ZSb>boV zRV`6?k*PHOr51Q{ov__NyXsRBB0Yp1mz!{M?mo%=3-(bOkP>3C^C{>V^ekWy+C zGy^LMERQDNC|k#La`N-$w{G2rJOqs(He;hyz?zGIHlJFq$>SxYfDED0YxNu<-`f9W zN!p1U^i|m*K`1we#c)OgWXn@N|MS89D)kEa(T=gj+o}N=y-`cUo@^2!E?t!yVf>QpaXOvGnZ5W$D!?-lak*fD> ziBFT0k?N<^vzIhr?th*i4${Oc5JyGP%@i-LUiV=m7C{@@jg<14^f#1N+f;Oo?u|7# zhNb>{)0gd>x-(=mXO52?s6p|-P&*-+OWbDq{!^x4F~gRtteD+%LQR!k9|G!wVY%&C zJhD?l9`Zxt9MWLGI>&<@&`l1|KZFIyt_c4Y+MW8G?VV%&tG^|7s8N1mpA;CZ*&OrF zmvd*kG>VoYTgdF0jpSDHlD~4S4r=o23~CBb*4L(^`k3N&!(Q3tcmmV-1gvY!N}~^` zpUzrw>>CiByfrHJnFuTb=|}t*J0;LrFGy~u`O0tSYK^Tzn@IL#XL%W!Rjwu%g8Gx8-hyA!qH{rU zGP7h|fW~EosiPV--%H(bP`tv1vH#xG5BqM5G+yjvy^~hX$&K9Ewc(WwC?1)o;H-5D z-d*2c3$88REA`RIp%|$H|QUP__K= zXnZo@08p+@So(Ri^83N^f>gEB5ka<7p?C}If$0l`b^jA+e{xKe#McQ~yhYc+)CP7cnqLpeJ& zpmZhm4XnJA0Wh@8vtl=eVW@3wio+4JV%j@z^UR} zG0j96AVeC42EXMZw4JXgx%EBUxh;n{Z#a*U5Uj^a)lO;#x3}R4hMnAS7I!h}Ps@C^ zp==3TUsL{sojqK3n_aw&+0jp1bD_k-T7!8Q;d%YWd-VaK@pzv`7QNRu^yScbCI#Lr znNK?grB4Jfb5B3vB#gxsNTw~a{K>FWxYhuIzKA=1_chASVXE+>IoMop_|trc zh8rmY@)ILWxPFZl#jdCkBE9PD;I=GC@z z7y=rHcBzhr@?TRFlE%O5G%AhI>t_lnAVuC7e}B_0tq@yrgOU!052^-Z@YZl8pMvjy zig6m)Dm=s!Zx?kG5Ju)TJLmt+%E~g&0{tfhDOLK& zzio$P+i$mGZZp8{cy0e=)FzRPT)FQ73ak6OOO$bcDri5ikR^ii_;?8&h^CP#n#M6? ziaPGT=BK1x&IKC;3Tn26gehSp65qw*3ZoC{`8GelDbk?~F_)XpY(z^6A5_DlxRo%$ zf+$agTjy~!vF5nM0$tGA z{G;fzDTmy_s|B$DDw+TORV%1qW8nMuC;Mh?)C@4;s9{81l)-$XkNnA#i7(k9tc9@n z8f*)(HMQ@wkgp%tbW-C{>A6hV5HqO48=!07hn&QCmLJdhZc8Jc_wxq(DhPu6_r4Kp9T#)?ljdYwx0Y!T^E6~2Cb^vT-bO)NUcrR!A!HJ=A zM@s;MyY1M3;@Tj$lE>hsnMyyRwrUr$Fg$Gj`M~~#4LR2bmloo{a!QAV^3b$Dg?`>l zMahyrzm%WIO;DPaevo(WiuCPuUNv~8A=5U{YqxNV zsDJ?!5mAw#l7r+V6cPmlB#C4d5XnhEVu=wGAUT%`NCwF{7|9?}$sjpv5etgqKD)qf z&$;&dz2h7AM~`vF>87goUTZyJK6B0`F{yQ74T|{reAF!G?fE*-iNhJHyyY|d`QNG+ z_NHL!6!#A-R2I$#KKxW~Ho7ywlO*{NIT!-}Sg(Q#XR83O8({E|snUnwZCxnrvR9Un zV5brjMTKQu@3H0Z4n)0MDbdHWu3ikD%{K2j5LtdZvUi=5TwCI8;fd=J2R?_-o2@)a z5<0V;i*+Cu!!(OPbyx}UC1r0tmqZ1#p`7Eiaf^C_x|at$VY%?>Z`6x{ucG7s#iCM? z5OO2YPBgmj=tYtjuBIo^#20~dk#d{He9WZ$>d;={xXpGTrDZznmmdt&iJLEnoF=Y4 zI-Ui0FF#AIwKW+l@3q!@OzISHi1VSeI6}exCJxJ=hcy(uWT9EdXKYhfgT z;#>h5I_BFij*^fRz!Cr!IcbFKRnOt~4S^`08K*X(s5*wF2l&smd;4~d81U`FG!|~^ zHrs`CJ+C*fFPQD8`EhT}m3B$K^wq0ZGmJHu9KV}X(05QGIlHC)<5@sn;qATYySSnc z-72xPXsxgr7#f?FB}B}NVUx~rp79zfoNbi+Glw3KQ7LWbMut4)3T z)4zT@Ki&3{1i62`O+m^JzbH6mwr_ID=ew_yW@){| z!yUSl#6B+-PJpRD$nCfPk}2>o{A==7(1CO8b3Z`ZDqkgp`>$?D{L77Vo6!~{Q#|y} z-gd?g;kSx&bYJpekMl+dsE#$J2d8edQq&y78sS$_T+SXCAoixp8Pw zFAu?CkS_`lvuv$s&|^Zs&wedJ8pMp0%BN|p&+Q?JgpQD}hvUozmghL%27@vgHPK14 zu2Q#vix^SOZp_zL*LNg*jzHxaXHFRnKiA7p*Tg=`%d(n1+pI%cG+SRTDoxy()iE?! z))Sl_tg?4{K=P}_-wJJh!_yiq#z0{b%ODgXSV(t;p3#)GIqW~1G(xZhH>Kzo>a#1o z`QJWxK!etwLf1DoD0{#bTS{GdE9cpXUd1^5^$5dnDY-wD!mqz(-8`)E3YX@dB6hOx zO|08{Mem2tGsCBM2i)XeDZMPoLzz{qo;l%@QMh~aO6o@G{0v8pX=C%{nx?OX^??V6 z!-LUJT-n7I9wy99sSOLbBjPxZ;CdY)$?=z#tlz z8aj_U)?xPOW(9Kdmb1lwZmu~J!kjBlxZk4y9qq8<`~(O#>5wLlP<~yG%q&hCZhj3q zsP%b&ICMC%Z3p(azaJ4`S1LwJq&c%l`;u#62 zzhzfr7?UtAcGNp=Lo^y}v*cq4sN zOQr5JGT#R33;KkcdX7Gi)Kp0yt>K=_t_csNXytYSq|W-7XSQ3Cm0Mdj_WkI5f@U;! zRDll{Pa$Rflg~ywwjo*vBXMnnp>1SDy`rpjn2>Duh82BFJbbI$?R`vNNyZtnJDe9C z(yNgan}=^vDr{;;^n;z<#`T;fIQxXB98V$5Y!mTnW**lew)qNIbcioP7KSXPh@ zSE>a}CGC}%e%&->;q!ASt2n;30`GKcrj}tT{d%EyicFJoSx6d=8eAu#7Pj722m}hB|34OIA zhebs5cf4ED^!p-?f8|X{ju3iLYR!I76Q#wjt&BgsR$h^D@o5?(wi?~@l^wh-%h&e@ zHS$&jmj3+T0N$D@4vyXc&hz9vvzCDv!4fiK1rMGlImGES@Fdac$2-gsr+)P2#%LBA zw}2w7w48Zu7od$v>Xfn?ZAKT)`QX+u1@6}P6}9pDS9=(sheT(3Unbzc2CTZ%9YBF0 zsaaQ!xl;|(qY$shR@T;uj;(){8Vg9~XQr zp7m43foO(7)KJK%3p3n(>)C|?hm&>BqqlaQA89r~<8zbOoOV9ixU@!@9vYqWJhX7Y zqs?=Ka@sDap!&r0#)|4vd?Ys-MY&wXD2A`)?kja@-C`fN!{#QS}ZY9 z-t_%YzPZuyTK?(FfJQS z7y0fmxCRNXmLv(SW1u}lwF|>d;S~nLo!gNAYZ#1?I|KrxkK%%Zr5HBkt#$|X%R7X! zKmm48Qx!luonRlAIQq+kqSL+*gsR#8!Lfl?k>`M|#+$!BLu$i(=`kL6aSh)gaY$X2 zA)1-FA|LelQU%WpTXO!o?bG2Sufv8r;9Fmx=`nxMO#27d7j(+$>OEu^^2v6CG@})m>sHj+n$v? z!n4zH_b!_g_@R0fJ_vyR$u7dnbkFao(VF;fNOTxu&-y(iZ%8Xzm$`5sdMX8M)g;K| zln2q9%P4H|k#$9JmV1fORsOohLEHvX;OFnwW%%xoc~g{(Dnu4o+!DQ)-$>MBe0L3oF3Mefuf1y)eRGd zGxrT?B_Ftk-feEF7T@I-zdb2Ns3v&tSK!CML=}p+lC|Uc(2>Aai6)cdMq|%>8Q3IL=G^W&79E%!MuCX^ znM6zE;dZ913ukZm1X^@Tou<82!nH8%hm`a3s@nJSqPMvs$RLFeZ33TVLH6+sGD5JX z#YYRA)7!p_l+hYaiCz!i7kAB}xNC#O#b9Z%*#mSdlYvmKaIc@!T7TMYyn#m<>q z&(&aTX2Wfvw1WmOlt?y7;c~jW^1a^8;l`q$KY|~z)2X)OAJ3Vao+dMcj*V5NG<3E& zXgPFtqke5hH>*sxWN9WGx{1v|s8V2r>#8!XUhp76#SP`V2h+35cfRVW|edQm79L|M^62NdJ>_}+r0PB3MNfWaz) zpT5+GzwBUcc7|KtiipED$4^IwWf*he|Bmb{X;6*H%WANV)S(_L;7u#Y{r(Bo`Y1g% z>3bkY_lusee_?!5W+8ts$^62yZebl>FF4WevzJ)9&UDp=?Syo9`2Ny}J|U2r_mw|&8iO$v z^5bdDV^XpqdHexk=c#2lb2Uu3X~DJN#^70G?Dc$9y|`fX{VtrAKUF2tPW|O;br1}} z@@p0hAq((8D&{#K77X@G^zhF6NDYHfFn3}uq?0fi;DISm{f0p-mQJiF;9UMPU-4Tl zi|q*wqU*RW2EzgKF>V#JPxR0GYcUpIvqDV+Q0GewyXvR2K6eaD{_6gQ`*Ux^#;hg= zM?aJF9O}cq!}JGV+v!mo))-wjo`Na%U}o#HC(A{y#kq=tc5lP8fr4r97!hX9kFY4G zVpFN2!R10!kKAhIPGuZG$&58bFrNB+@#p=gYq6+AmHL=|p?ef>yxEgivh>Fi{Zj(w zdQx4iBl+!$E=CA{mC#A}>~8nLBdf2cw7(|NJ4H%aaDNK@d}81(C3()$SL}8$JbWTj z?VIvqd9;e z!o|$|wZoi9)$`i#R50Hv)>h`Rup^NGcgFN-6w0yO;W8N8X3d!L(5`o~?(g_7hbufC!R#K4>GH(Uf;D}d$$ z=|cRC(w}#34G>8@Z^dGk$6W&b2g(wZ_MbFLvv8OdEl%;d^)9VnCpC=Yo7aej;&>}u zZ*J*c<=a2WxP(B)lJmYg^=xZ1H4@eQ2mqY$970cP!KsElpc+LiT+Wa=VOec%w=j@& zogTc4*GRcCHC)-JveCn9MA27~xT|Si*zTrNPk1VI!e~p2ZTINs4pf`S{r$&vSSyRr ziS3OM^O7bs?w2w6o{H8u>{5HT;^=#|a5I6bNFibj3xU}k`%}N&5bHh@BN*LYy*GP( zSILVQ(chD9&Qk-?@h<+y9wDdp7Td%dUw&KyOqbVl`1D>*cu#vv4{x4OTIXmu3iZ*< zzvf?Jau_zKpYogw0fv)|5@YmUskAn8xXqzn1+Ip#PSNI0c_}ebr|NjV_^_4wyKy$Q z8|Z!85s${@7F1q;;NUQ#PjpTAh0!UHba9|V?f`7ue9BP3;Y!!>9z1sZez4ksd;tK_ zyx^b9!i93MO@f}-S9q}!2f5p*E+P=xLUludnn2POwVY_BIN1z{g-8l_qJ5O7)vT%0 zwWKEgEjF@Xi_5DU{W)@%dt2CaZ&hB7Gpf9d5Y!N|p1r7dd`zlN;*-ZFeTk-XVk_x- ztgJqhW?B9rCnYMwLOkNux~^sD>*jpwT+%DY9+>RR#kfpgKmQIy84vK}NBBYueSXwF zcf!e!UzYkyl8Nf>_Q2$}?*zpT0|@UneO=(mr1bLhZZT|fK`Y8k^`+U36SG>{FXnLq z)1#^VLalJMl3CL;a{lWLht-QFNCuT>l9`9}#}+f`PA{206fTulYn&nI)R(pMEol^f zN~y@uFAUpe>XmEBuL+kp71lsdc^XC$4|-9(Qx2;HfD~<;BY1&U6or)RKY*=c%m9TQ zAR1#8ise?^zW(CMG!HYE)QXFK{3)U={~b{dmjXG=Q{>Yq2AcLed8a)*zaB4k{U@{p z9vYJ&%~2qelZCzC;$U_d;=CjzQ(#fZof7bsRwmn?8a3N&=qTT46l_(#+8o!{`uY=r zf3ehbWUt~$d%?!1ic4p$!apl)$D7FRw=GM?Q{h2^K6LTNArB#l&Rkw|w1k@<>cK^& zM0bH{r{?04`M>7xU#h_WOnR8|86jZ-B=_2e{O;=gn=&&Yz=F@K{ar=#DqrwaE=QA13X?B;P6AU{mwYpf(<(Xxe z=^&9w)~ec*)w{i#*R{QJZ)`uiOHa7kel71M^4DIEwWok_b5MKkb9T;g(`!2^qzsBu zXt*8|1FoeB&3&y}oQcF!haV=DN1--19;vpXFJ%B@`>hBi?f29# zwI_|nlQ!Jx6NW{2e^T&UizQeu?aQQR73m1D11dn$ll{lPsQ90onlM}o+Z034LJ9f= zsZlFJ^0?$%D>`}1=Fc09=v1KbxKPR?=Zix5kLSx_NJYHoq@?flRz+0pgCb1`WAU10 zc!tVbxIy*#$3bES!uHrH#+07IyeeGZ=l$O+XH{w$xC8v{+IU1V36T{{Hs6xPai2Cg z%RQv0;z@(oMh2G6W$V87l)54SpTeOksFd&WE!;znk`jlXQmNA493n>aY7fL#Mzo*r zCDOdbF6<*!<7*b)t*q!vv?JNKZ>2A5I6&ffa8Sj=&}{aY+pv8cLfTA-S!_vT$(-rlw90@h2fTA`Y24$o zjNvrdSbK2crIjsdb3W2pW(-_ELbhX^7-*YzN$!0pEk@#{#H&~{J0KD&^SKSpQ2fjFDX>J*13K|6eSvL6wqI$76r+KTf;vE3sUptVY6wKCw55 zxt_Sn9@MMY*u$1_T7Fv*is*81Q{fKpB&qxfQol6OWd0jczKlY?m$wS?J#y91=D@;C z(cIpSa4buraXWok5Uw3iZBP_20>eH!df`4yqv*Ug_P1hJ?@>o;EuGBC@(6I9sO>4R z3DY&{;(&Ac&}$AusJ%T}?^DrP#J!*CD(4Qn^&A%qJzCOU;*8Z3*e!DvN7H+4N#2;W zGU(@A<~iB%!S+gef5aV2!{-cqN@^R+U!PScGLcdo{Dxbz#?%(8Txp@Y@QCGY6$?lCA+~^`v*9+-ptN_-mL^CtNhfjGtu+^uBOL#(R7Uqd*e%J_3?kjo{ z(Ci|;?|PlBiR*63w7YQ1;KO*U?+qx*GO9Wzs-+^pW#QYj^#ecDYReYaX`^Bye%42a z?K#2L#_At}P~Db_EgHqe#;s}n?3{lvJrc(CJvI^7Q#dd;+$Zb;1%a>H$7H^Fg9>e) zdDrJ$6)rb&gJqQ$8=!KHu7=D~1C_4FW`+AZBkTjy%888O9;3`4#m?Svi5(**0aj__ zNd(Vt6CTBOKm2-+sf*2CoNw2FKt^L&I2Hf-xbVwxo366j=}o*n=0IMPa{SctgWOSP zZv7Dov1otUMg}d-yn9tiuq`j11^@+_i9&Vo)UtD@?-$b6#WRwN*N-v^k+vSvRo368 z%tZ$uS1hz-Ew|n+q~xx@kV})Zurv!78;NSXm-lW*uWRL;bL4*+Ziu>_;07!gFr74t zb8v_JOauMKcxu4OdHjLcb1ex{1Tma>6E^W_RHFC(tyIyJ=rCEKkIh46-CNm*3II({ z%l-4&E@`gHCtY9$Vi%`Wi&5Tr45!5|w!RL~%Oj6#pEzrfw(UuDIejHwqgglq*6!Z3`aT}I@hi_{CJn_$r=eCdZlo9L&z=72(OSD{ z$bIjYAx$by%SICCy^&(<159i6Y?t+EI-RKRVI!Wtc%>lMf;jnK$Isu4Vou=?T;GJs z1c|#HICBD;T~we>dD4iUiPrlpIKEu6&VASQQT;jVl5Z<3!t;JyDsPwN?xGs z%03ii2IcVrgE|{HsG14xYD`<`3ejBx;G})0Wf<*n3$0IiYf_Rhu?8yH!6?Ep5sv&i zlO#o#&IhqB8Wu|el_4!j&Mb{ZpH$YdNvH>6xcJl0OzI{cz{QJpCZg5r*+H5F7Z@F; z-qkIq)mJAtx33m*$IQ~)=FwTGuAI|q7L^FsOtPldSYUne)$frsBOfBhIcjwhFvinz zNcxs`?$MRes4-;>A0!-SaS2n$p!N{RhKi?go!p~2yWaQLMmtqrEt7K z^(~HQ5Q4d2lg#UPmbEG1ronVeHFC+c3;%tuvG*x%7oS2$*>^n^izOYscy_C8DnAz> z0+#$M_hsrQ_y99}FL#P;1PC9ISD^y2Ifa0t-;T7U?;&|b{&5M8_{XD+ZKSXLIk~;# z^j1_-=mZU|c6Ta2J;Kf3=vP|}Kpr(iPkO*bC|T*{pk(a=c6xKj!A2lI!F|Bbj;IkL zw&gFc2|;nL!q=ukSF<)Qv&)T2eWF-Mr9O6EDsk#d$g!kvlR=ElnR&L_5I9q~jM^D5 zV3gh7H~Q2th^+LPbs*%7h>uE#ZK3bqCI2}&WGk;|uPuL}BsoIuH>KinnF=EKVt%hx zEaY#6cWI>ybgQH4N2Pe`7!uSY{9f@w>SrTnR;8)g!Fsp9H&N0^^iP5!n$~5FbsEE4 zXvxG|xlowSdk-fI%ZtpmySb3rcB+4^N+tSLZAYJvdmHx7PUl^oG-r+SbPL5+17$y% z@Q!}ujg2Y&EK#|vA~tB%upY)6T3>2(>ZyG!JLEW#6t~xM&1I1;{b#LCBI?c3>%At? zquT*{JVOsKD8nAGAqgexZp z6o~wcNDqL07YSacGf?iI8ejTZc2G(cYw%P~^hPLHTpO0#<)yMlDjf4-m|W*g-H^kE_^%gOgQ<-5CLfh)g3RfJCVt za~=LZtLQT8^+loXQ`KsrU2WA*gP3D^*E8L|%lBy~sQ=st_>|I7$;`Fbk|2Yp)Mu_d zF{;fVW6u^GeAt3*D?L_j!B!l+*}`t3yOjC!{_|t=T}#&GoJAYW9sCzoc(oUjzIkBR z*R;yX!(R+OWnrc#;Utl_y(#qGFR}tO;L)hLNmM z3v)|@)nd*hpDUa&Qt7Xcl1sXg;rU&o3%BN4oM*k#n?m358N-~oo_sj1ty#RVb}|lV zmPXkbyK3KRxbWLw_MVgTN53Lyr{aqz-EYzj&+DcSE|^koly!Nu8{#ePtxm*_>0BTH z8kx=F`AVz)h~ULWBZD{^+``{TX8?((8vj=TDGZH&kMPa9{~F;#OyVZoSKI3GD2e4&>Zlk6eh9l( z8x!rh_$9W;#50;H5UB-=yp%#e1*7yiQoXNqi|QT_pSYSrr_DJqgQt%+7V6YAC*h#k z*P=D5dg0wL`|2}@zb|geRUeG2y8g5o07O@jp2a;hXSNaH-p=o zO4KEXZ32STOtidmG#9EFA}BMBnN*H2`K~(Ca0A~b?_93Au+odNPR=PwIA%WFq^ z-MD>q(Cua!WYl6_3%?=U=pszj1AG(0;;hcx8t=z>`qCkZ(Ix?CrL; zwd4|RR`1D>h#O6BEm=UEJn6#h+gdi*{?&m53q=+|3f%myGZusE;BNB)Dq2oE#(q|BV3%p1M>UzR1#=G_BL0 z-<#le(9nk@^dk)^6BR3L5u%!lxJB~*dy7C82J>r&VCg{K$#L{%kMU4n;&bQGR-OwC zBBwsvbe#V_^<6`7LE)F>*t<5M)Xu~*2nBc-WuA8Iii_D2GU zBa|Iv9}%}~K56p{FuzJAVr!|p87Uu0A0sDyfm*w-kU2&FQ+IogXX@r7mx+? zE~BsN^(O$VGZJZ!FYmnKBQ<2CO2Rw(GFZcux;q@^-3sck^(P{4ILg6moj(SV{U*yS z%l}UMLLt>t@!`fac#{880PkbYcm@??7a8^Q>#)C&(H~#A;l91TT+|@TabL+1avM=E zSgtSV0z9ForLOZH6qVXX#NK)S9F-6i@Q_m^ite7VSP|q_a`+CB=78WPII*v8*$@b( zAYbuDyX^QFd^UHl9wli5 z6dVnrEfmDJ#t2}}NI-@}eF@_r4>3#kO<0Ulu>pfq_U8X)D!pZ<0IX?VYHp^h)bL@d zrIB+8xub90bbZE#XSM8Vlb|~^xBRYH8_O>2ogf3;(4KjfjfhwLx7y__d*(zVr5qCs zTQ>BO=AZO{?`)P`=(eQU=}KCs@49aM&R_7E_(}FZYEA=D{x-KL!XD$5-m!?D+hs5s zaOfo!YbV0(ed=w60TJ zZR2=3s4{{9&)^~=+GXaC(~II;BybBeYxzzy;8G6)M)!@5B9Afz;sI2|)UMaFGd&pS zpH9Kq7QAH!QmbvA{7`&$<+um0oLkDxizNg8@DEOyI4+`(o!ky-EtCy@RA(8tw%l%B z3ROmA1R7v1(c}ShEd#QdzEZ`p=JfD1kFOWfJ_H1AOU%vCP#S!%L{njf$&vddhNewupieTpKX6H3qY`Oxt zvUcKvNBd0Y;IJ_v+v^}L_%0+Oz6*gUyE%z8Fs{l`mrgY5EA&d)M{hLVv8M5U6u~oa znp|hnz$m41M8oV!2bMULz}92F7TAXF+OOrDW2~eXPm=7L^1Z9Ue*d+LH_$8J5bRh*B|Xu|Qs73hLg!NPUTuC0$bp;W|VSl#R+d zGBWu8KlzNnCXOi~31Hzx9$|!ra8>TYoxEtWYy8?*x3CK8)%;gGNoQDLQi%@GV?wwF z>C{Js2al!DiGm;SN?AJZnb3u#F?Ei@2TG80nGhic={YsReLt=e8O9H=&*=Kky*YqT z*A9}namBH!91*JNnymyU8tWI*2j@MH;sg?hgu9lS7!qIkB%JtyT}a#vXk@_a*&X!^ zzF6Y;^2FE7=k1-1VN!j(!S-HD4ON`o|0S5)xsn7K@~Q|iFwT)#xKJenYMw-L^Hz!< zh`4F4#cRot!n=AxrZVV6?c|4fo(_I+uOw=H)rqkBf7rh^%y7H z`dt>?qm-5+qppDi)k<4xOE1SB-Iy!}Q(4Axc&y33<2^SN-dXgx3K~pjXAC+QOemrZ zDoLkMZ!b3qUfe^>K3ZM2CZNCzI{qX7t6S~;?rG;uAJC(z%rgy-wy@bq& z-!zn~9-BAjwuoCZFLw4R$FDZ6mj$EL(>F6>ZhJ{g_RaPfqlGe0&QA{51syQTs()Te z@a-85L2q0S&JO2|;F#Z-ltl!1HXf7a^X^j?9p?^$=x1WUQvsoUA^C1>elIuE;64aG z0tQA)517%Z6}!|xXk$9Qj0X0Whvn6cN)t|tIIR*EPy&hLaxLarHQk)!4c%0A#X!Gh z){Eu}v_u{IPENZdfmRL=6T7!=q;qywrEzLbhjJ@6r8+*^5(Hw2k*WK~-LG@cjpj#M zE3_HTM1^>15(CqB4}n!IJ+0nnp)H!tXL2x8Ha-P994ROW)|Uk{IKh%ELt^-I+4h`d z{PT5sLvuBfe3becB?pf$k->Bq1evXwcAJwsHPOS;S)Bogcm`&E=n#1tnn}JC9pI;P zQs~3=e6MzPM()RWtVKPiMA`Uso0R1Ra?kB?i}AI; zoMGLK=37wY=#tGio4-mIIPA;HfWFcxMc6AgJd>rAb`Qm?NbeHTa$7{r_-1=kr$T5u zUL(mNv;3M2_32>6{aCdDHl^Wkz7h>SoO9D;(umsn%s1R+o>7%0t>KF?`D`mOzTPE5 zzf(Clk6S>HGn|<=wcY_!Y_cw(**VT zQM(hI$EgING)pJ)3$Glk;UXc?Kx`3UJano~Q6S6|C}U1GAG8YK&I#qNhjQm)MO@1` z5YvWK8kIzFyI5opG_)cmgoG;V;r`JVIIyb4)In``Okz+56> zHk{{y-9RhJ_}Al`Uq%oRQn5bX)z-i6c^dkSJy{xq(51QJO$|hZTRxt~+}!WH08cAh zN4v|d@p=G|8Mm}^xBIyj9!S4IIA!JDk)S7H)#@?t1A&jLZ3?URk;YIR)W%FgK$w(A zBJe{cDLK#$imrucOe*^N)&pyQ@SkJlbEbvy)ZoRIG zh3?`{7`fH9etyU@X@r9jj_F_gS>zyDVw_rR4S3VXoWIkf-p{xE-UqxQrJX_Q(O3;d zBeyAtCQIEWAZIKVM4@d{g4MieH;WM&WGYdIx8okMsv zMJkMbi(uXoKs}Ylc)n0@a``8Fbe6+?pI>~&;AS}vlQ2-MntLFL`l&W(B!hyk6F4Oc$ZEYmW z7dZV!`}Kcxd5zcgaw zxxk3u2g-#h*-0%K!~aoKbi?Z+IyZD;ByQ_ffCpx!8DixJLzrq4A7}CLf;lp z`I39%LDg4KNhjYOA_Snkr;A)|%M8A^bKjZ@2{bv8A~p4}c$a|B#Pe%f-LyobmK9)+ z-6eFr0yZg}p=?uz+_x04DX)dk#GcxPneFSj&Pi0uS(@BPzk7j^VlIkrf17gRsLO%%_|(( zYOiLHy`^i{dy(fY&GvoXDX4brYH!#>;IOlLXh(%tj;U9iZnZSBT2vAdsmo|Xvt=02 zTXoa|ofR5+Q^LwUgqaS?zQ~NsH5sM#)U_j`lF*X(_V{Sw+Oka*apOBFT_^+XKdsNN zROW0Bpj@NQpLx1jZ{k+pRM;Q7g2F%bS{-_1{wO&kg9Z$xE}9=_i(L4)HsImnxu}?Q zcWKfmG6tJv0)Um#ykdT%`fQFK0hx85CxmQh$?PO60w8|4KMu^Z0A=B!0d+bt+dA&uy-6hM874#GG4b5NHMBeb5I`!fNvL z8q>OU!fZ}c=4MSqv>fg2POwKB4Je_p>3m;W?kZf5xp~3D^DxNqzoFoaxjG1Vl4--M zg}K`rf)m`4jsn&7woJ0EEaclbrcu?%q)@Yx)`t@}QPo6T1Ev**91W(}B1*F7h>) zyt!w`7i0)U+06tUW^}{K30zxDhehkS2>dV&T z^Eds9mEDmtqXwfqaB}T@)pbbaPenw`Re%j=e*F8lTfb8Ix70pk9@xK|FHo3lioa!_ zIp=)YPJh{U`zXYJ;Icd4h&dFk(jETkMRP0TCD8Cb`TEp%$KzRySi8@fq7Mx5%tGM0kSuy`bEvkwL-RB0d)Qm z^JhU2t4Cu6cQ;iB^e2+z#~z?=i!?C#-j%07UJlpwoBMa{frUEpZ6pL?kA~RXk8gud zTM<5qGp!g$7<4rlhx7>}u^pA9$Hd;cWuDCo3V4J0thDoD^osTKFLOtiOr+w&_<1 z>`3nM(dQxqVduRwLsq1^OpYBpR_BzmeeNc$9WEKXxEH_|_0?y6dA7%*^$^Y!=$=$> z!Jn?WLQ-}5Ng&Fyk4|Ll0p8IRvympZt&Y?IJP8i^$Hpanvx3Z~FgLr2)&TC{jUD51v94U);_7p}wBmwewdzdSAov zRn7Q*yz;yk3F1bfyRNtqz;Qw9`e1%*X5$N)#+3KjcOeA)&?NW7Kp34DJ!!nx(gfJ-Jr;`H;j48@+PG-{| z%C0vhLZ%ErhMJ^dzzqL{Vg9vme{1}H@rS4$At;eZ^xfvMbWo*TX(<);HL~B-=+5Vk z>(@zVh2MS;Kg7Eix+BCP=Kf=atry3Kyzc#wleQmz0*(~0;YTTVVdBvT=?;?UK_07p z&%>vP92F`uBoC=Q%j4bN?evmJs|Dv{!}F6L)!QIglsa40(bu35A1x3SU&?f{(QA);qq72+ZL zzWmnWL+Q)#ALf)ecSXa^kzG9k(Ko=AMR@j2mwr$Ps(Eva4qQ;Hdp~Z=nZvu}sBh*2 z8YTv_pC?VgC>#>@+*rHucb3zUOU z+W|5I`iHC)DfCqRU&ia*%Dm{x1(A=Tz5+H+wCKw)UxA)1dc7$XDagL5F@kvh;-U@O zC9MG?q&Ib=A^d}W{*levmq5x1%nr8jTn#-fUZN@yDU#c?z5-YZ!c}S6pp+W91lLG^ z>Yty}%T;T_b?@p&(;mx0=IjIPE%DV_-u+;$*`kwNirj1JC2og@Ly6!=%Xjx~8+rb0K0;B!QtW4;Tguhw$OIj20-TQz63A6-xgrpwx1Nb^*^OYTN z9V+5MI!F3~^)85)r}qRbs!_7PT9}h4EpxS>_c*oE0OR5M=Sc}IfY1fTX4%^_2Zr3y zuehZFBHDn2CDyDW+S3O!B6tT5`kF;N*|K6$m(My7OB_!IczPOV(7=Vz`Xla{aLb*= z%6CR~+%RfL%P&Vf(Rnk~Jg!J1$+^9fR`6ozq_Yn*F!M)SKS<#Ry;B$jv>*CMP3#{I zS0?bC^qd&S_C8!v{j4<{a6&@ohB^Z;@Ro($WG*x(c_Hpo4aeXA!Jb7C$pu{#hqN&ee@kpHzGjGyZSFYD}|I;Ta=2%`2Y7i6~0Tw>^`%|1r3 zW4jA7&ZrZ#nbEhb!qK`*h8z;xc9-Rhk8ghR!ugY({-C`rDB|#NnIPS<0zbaD$N4gH zd27`!5~Ui3PubsWO;Q7MdHM}g$J8(3hO=<-Q~Pk!JCNC8Vg6e2ns)04%JlE4D@X6e z@ec64H=oFXer!bjDl#%KAK*MDU8M}MgyM(Rgm=(tN3+)2^bFB-wwqJfo7yX6w;cEepB2U4F|Dnl3kCSk^sHXq;8YGG-5&k#Rv1cZMF9G2ZAn*?-i z|MrzN47nMX6(`4=(^rmRoVw{+N9&BuCBjPe3upe?ya{vbGx8E-hmnWl6@MLs5>{cL zr-5Q(e$Q`_kM%8L+~>ecU(OV$gD^WDSTPfMdA&j3QN;+S!+h=Iiy)I8X(Fd18b1e= z4z6viyE8%IZf$?c?`*s`BbXDKuPwlo&psK!vk`5H(Wf*kF0Y|)ydKl5uHk7TFN9WV zzt!f-ci8>_dPm2C)@Fv40(jj4y>AOQ0XnMyZ60W ztYZQAg{hT1GxA65SrItCPH1@L$U!nr;40#-gmFc23db$h4vc+R8865>`>Oemrz}C9 zz-IZ%{!ELLY+ne%`e+ZJ138ZB;ZSVClgm?_cA*X$3@&MpQD^F@SwVHQbWhQP^%h>_ zRkDF5P&9il_J{P?Eg3Gg495<<3P$u;Wfl}2m5>M zguGb@@pN(mu5~^H%KnMy3n3$y7`UB6q(Pmu*8BJfOW05_M zDSud!Jic0|(z>I>MeQ{EwUMmC;c(OxPMK?e(X~AMVy418-GkQRTXkP`%B|1sNc`;S zx}mQwj>Dvx2l_vd5kf!7V6DtTb=32s^9I=q>?*%eXbrHX{cI>hvdK-7^P>SzTgSm6 zjfn5wO_Cw`UEvmpdQqmlk7UO>`Dt$SB0HUnlS1P8$wgN0{TY~|iVD|0>Hv?RiPp?M z=OkBc3G@@~xy{_lK^~&(@c%{4b7pnIFZ@W-oWxB3f#-qEqUf|VelQZCY_tFotLyH= zlw!fGyjq6VikVH%pfMV!9^EK6*0|zbFHoD~F;C5A{5IA7?RwNIyy`3w=O5aLcBzA1 zSs%@wZb+qKsy`?_U&Eo-7%Xv>=*ROr!UD<&IBx7x7P@?f1HCbAqVmXDjU6#;CX*R_ zkRf5-SK?w`+TPizJe;t@yr--6YNcs+eMMnhJ;CXK6{ph=K85LT_CQddLJx;*IAD{w zn2DhcJb}H}+wZ41M?XG-p3;`O$<0^cEU(^$ZGGDRI9gLaa3N8V9ZcLuX*GS^Uyl!| z=VCW!z74D2bUIc$0&W{dYl|8LkC28|qL>POEC!=PC}~3+bnEL-Op$s}^$6tZyigVN z!{eqZjd%*1;+W?v7Q$|=7TVW#%{B+voYXryVIoziOBl6BH@w%@600u#njRb{=@}N= zQy0pas2=W5X+l^`I?IX8DS6 zLI|3k67@D!uMwQKC^A?##jNl>N1B!?&V{GqhD}ydEMjIITPLlbs7F}=3ZuEYr|K0u z(Br#j&|E@(_+m$_OxD*dADkbTk)SSo#U>}r07gqC*F<;tL#1XbU@5X)WM!R2I2(SP zcIy-?tx#&|ok8riL3r_VAxUyFk0bOzVq(kAv@oIKV&#BDdl-VKmt1iIc+*OpEizt; zI;lClSfnE~9T%_8*=T&baH2T50<^A#3{&yYMs!a&s*xKlNoX%*&-LMoHt~9wW}lFV zD8|@s_kfUW^w%LHeCf=g(jjwVYt6{zI&H z{ayIH1Ac;@sKRX_eb!b1g}AY}hb&_n>Gu$n8^NriEPF#I@~pS<<)3HmiS=|1o9|g{ zHLov{y(kHbaUHCn${)HL^T#R^Ch1^GOhDCJ#5u>c?>oU`QOIjT+Cn!-tUUiBJ%sqT zf&*;-3SlM6cJeBu5T@GSe$#ovea}Y|`#~8k$BxFgCT&&?IUQ-OjuhqBW3x123Ass4 z3&78J=IDOM_z+Zq3gd`+ktis&MST_z5XaucK7?j2FgEEYn`2diZeCNvM`8cZ}bN*XSyf&gvJt=UrD8_|n(x{14Z5K2N+J8Ogc>ztD z+(UkWouAmz{5#({yslx8y(Aw6)Azq~IY~VO*xGDIS#ZnsV)3qE+1S&;?447BBX5q* z%ewEoP{cy|t2d(A?v0SH<$?a6s{(-383+}6J{}hFd17OGu}k)br)T{)UJJxr*;0<1 zJ*}dq9N-K<5pH)W0j^&6JeW4j*1~xwyre!54E+6)7}4*`Wfvdb5g-Ml2*m;vTjeTF z(h2MXYEw+a3=W9?khT!bCK^Cc)g19{jAYrSLd4bw-wMEbgX1_HrZaBde zibJ-tg!_9fD!dRkB8Ptp$6x2;eH|u-)WbT7%P67son2_u`45T6?i^{c&3*E~y&7RZ z9ev54zy}Y;uVC&XOQa0J)js52@R6?+2i|U#iL5gQa%eJ98AcAA)&-I!7)DqHO8d(l zs^792OFsnS=%U!+Kd#p6Fq98@9#Fx&R+CoDJ2TwGKLkJ6zBN7vsJGO1)xW<#q&_3I zNxnrR0VX8*l4DmaZs&aYj<|=3rz!y%CRGU~*$n8&4`bL8pVfZvpzH z^OlbV0!4N81|bTzX2sUEU|pO3wJTr2Ztu!Z{@Zlh+;I$C0$l|_QZ-Onn4w93{1>yV zHcUjc_{7u1k?UO?Nd=*Xepwgs=AZZdCX05K@hUC!nMUi8V;vwqAM49T+a-8+RaUcb zp5C&D<_%tD?|jHRaBZSRgloIeT|WW}TYsd{&1v}$#>)E#yMKE!Kmva6&wsftykrE- zqo@jq%YQf~fv6@MmkwHBwh=q|z~#}!ogZqll?|%j1^PhAI;LcQ&xqbg(ucrREEAJTh&0FV?xhK2@CDcre34R1ir#+l;?@OM55i%O7>1mqeF zm<=J+vlI3tzim5c-4<)!Y&=&QH4e7SLrHu5~4|S1S4#sqaKU%B!%aq?umIK&y3d0-ruA~f?V$+q9=;L zXw}hG;qxF4e8awV?)bb7ZtmGp4XD)#$~&ata47D+b=MXk+4lXr_iPxpn+)OOPYPJ! zttOQ?SiCrJr2Bl8BQ)gIJMWAV8FzOUU|Vn+lKszHfp4oWxg#wI(y0^vr~dtH1NPQh zL8J~qtc&R<^nM4K`-wgObKhEn0T0vVF}RXoW;Rk);LTvJYN;Mh|8K8zjZd~F*S@ug zoZE&K36j@I$wbe?iTx;?bp1sQM%(6IZZMpS(k0a+{(vEV{K@j~PtN#m6nwiFZBBMP zgUm?!fElr&Wc3&E<+0Ea5o67i_3E5pIaQ_<=4R}!H8^xah(Gfj>oL|a+&57Vs(^ou$ zPwNK11P$}Pb zTd?}#9bKoRxlRD$`gm9s4$lc~y0&cvN<;-WgtKATo&I~I@7A-5 zUe)JA`BV`LWK0!yd?SFslRBr~i88TklQH%gx7Rb-z3@o-I{fF4U;Q8M-aH=4{)-!L zQM9U5Qg$H}A;~(5?2&}*l`SMi$U3Q1gt25_rb48UJ%m>Kk|q06jAg{gScfs5bD{O_ zzQ6bV{9eC*p6~0`_mA#o=DI%1Iq!4M`+bfhPP z#YY)pRvH%x=U)j`jas~&`<)|n*HZOBS0C@FgT2d#2o%(?j3c!FAD1zV?PSCJd1sgT z;F`c0^xfA*<gN(n(Z8yTS+<5}rg6-vjxI^AUdBwGK05>ul#?vsgc{&22sw{+Yw>1eWGk5U|Z%gOAJjk1;N%|VEQ z&CZTLLNYmi*Zlle@I3Dh>q;nrZoeSgb0;)TdGi9$>OS8{k$&9qMZCZ|G?RHevL$2l zQOb7oQLsw{%pFTx9ERt~L@x9!Mq@5Uzy!n4n5us9090#7Zjyx`QeI%vw0fCT>{cqM zP?8k}k8E-8P`VjYdKtLCjA`0qj8KYycQjkv1Q<|nJKrZllaPA_v9Tg)M$U;>zmN(i zRPRQd_5$MgQez%2);J20$((<}0rUO4%COr;4?*iA(#<<$rQ7z~)S+|f(FhBqQUYbE zdX>c;J<$kTT7A1Kb?aSm%EdsgoM#+6NuW?|rl{W17l6*B#fK*4De;z~;ZU7Hd>yOv zsz#_{Ne+SaF_*P%rjcVp=P1(YH+hmjL%Cz&F&jeJ3OoUrltFnduPofuWATyT2!Pcv zAqnBn8&G4eqmR=-lQxU)aVe1hzJ6dP5{J+YF!H4PMj3MaHgc{G0pn$Xd>)MOiCMh! zVMH8oMa~4Cx;LD|q)p|wPZ$33X*TE?upLZi{5AV+(TIA4PT|Gz`92AMF`>tWpuI!s z$9o_6a`!ltIKm3iTYAng5V;N-kG9~Ao-Wm<+kG$Q{Z4-C~S&v&q{wzS)rAJ~t&~S-&@LvPr+NL3(KWhYt^B%_w9N zvCDPTSx6B}bqe&3n+hn^QKFR(M!Q*62yCQy~#4 zJ`Rt*wb|nO`slB>nMI9qdOl5$k*E;Um`BL}@{&$M{G*Ce44t~9M$ycBfx}xRM~fGV zIxfH66pI5wvhhK2D^dd~2pu*>@1|n4c2k=8^bzD*K?LzFazuI#zZuc`lMR5vN$PwA zO>Wl_ocd{Q^yy8k3rY_T@@e5MrWc@NVa^WPI}BVO-NBJ}F>`%uy@m{-eaq$#%lV@9 zL%YZ-jZ*A^`gfrY(AV;19q4(humwkOm~98nSy2XiJ}8ru)LSA^yq#b8j7dI{6HiYN z6N1%M)?VBZdjpxsr@*4r78bV$8)ODRDabF0cnBDkFINJH^JJI=u$=iY*P4ogo~l_h zT#>BWLTkpcJ?SpboA4(I{{E47t{!s8>h9(`;Bfby#ud3uG^#U4T382e22jszS>vTz zuK7sL%Cfiyd&KH+sCob3wKDsCA=gC$T1LOlH@ie+I~P||ri@(Evb&u|1`3P65c3D; zx*V<%26SCh-D~x}Y%)aa#e0VyLELf&sv(jSt$Nn)hLO=y#j(t*whU{&{nDU7cXc?2`w-`r zd`gxg-GM7eK$C}d@w$&HdflQ^cxQ{WBmeOu1TXSfiey_ebZXZW5R9cohF}Dle_3QK z9g1_2MUyU-Fyb`@JU>h(9*?}>9mhkw1LC!LnG5o!k$vhK{;q83$aJB>%-t*f-8ER8 zw|#2SiJjeEbkSnM`e<(2cE;rW;@`pbHa)FkFc9Uz$uL`)+kNqZ;h|Lzzo_3kRJTn*6Ia`|iRnCH-g1(~-`y?g9`d6Lf!sMoLvvbW*Xw_;!s?TqEUz`!RiJ`P+Fe3^|9^2owI0uy1Q=2d~x zliR+nLnJ#IQnp>Rx6I`pD^a#jzMv;2GVtA$e!BHj3;kpux95(^(2DCv2l~a2nIX^#CUfP$;nOn~6I-)t-F4bLpqQp;9A=Thoa5OPQ_^JQL zkLhVxN{?lpGpVp%+Wnb<^GJ2Z0AarG*-GQ9vD2=5y2Emw*qeQQ72Ic!l`6|K)S)f< zO8g>pp@qtMHjiEf!-R-`apNM!O*9tR|b)Z zD%^A_Bl=O5;Z^(kF2bRV;>-f{GgYDaLJ)!4)xFmYj!}4wm9Q-ov@95o)F#v&D4H$CxJicarSiu~C;f+cX3hciL4~nNDL! z?RANq&g68b4rup= zJLaa&q({4dHWid`R+A)*#y6Kr^9Hx`58fv$1J&;AyZa=;+V)QQ!#jm@Tj}`ktMnTL z`&v7#cYlQLHciD3sBVqs#jZ*_X}85<&PP&1O61(JY4-6BHn$4J$7fdR~}V6yASs5H*=7M*QQrv2~gghR2;&r{yC~|HoxuS`(&MKV%4GYmGcAf|U+LkuD4LBpJ*Y zyn9wkCrmG08hlUEVq4Fffm8yS!C`Ddt-ynz=b?h%%$m93!nwKq5mKY=8PDfWDY4KB z2bI!9u9mjH!2Q~UDrkr7ZQX1MbQRMvl49l?-!sdy-q;C1gZWaX72(bkhvHrU^>0SpHjh8CMOa!J} zW#J>Zo-}fH*HW4aHEK<6J`%nl9PYO4b>kB&;Wpc5Pm{{LeH}yilaK|1%GKIb4Zt3g3 zd8HG9s1B0mFs+|UoC2j$Wq;Q|AZn~%zP;+mRKkI{lpVCCMS6V3)sZ%t{_YH|_R~at z<(`t^i7Txn&7#%Zg$0RSF(_9L7nTT7i;Us)<}TvEraeK1irQbpJ7qpPQX2WtRwLvm zI+Pg#IbGq!aC)Y)1g4%?+BL0-7xQ-)v7W56&4lbBZ!i?3o&Yq<42`St2t>IMeaLme zD(s7TSI>UB%g*gODR3zEj~Gg`5y*lP-ou^8`j1(-Mr4Md`kZJ&x=EU8V?G8 zfg0>Ydr?J#f8qUnw*mF+fdEvsv8?ZwP(%rCvhM1a!NI}HJTUiU17~bH?4XO)N>Utm znB0=-uIB#m5e7_NVsZ7(5To?X<_PdvRaNm7j#M(Q6fVuF!bt5jrx;R(Ad9MKNz(jc zW1Q{p9?>b*Z)3o3JD03O36C?GvN1M3LQoW3Na_AM;6pDR#)8kV9Tl415rLi1FEjUL zi6vjE?VPK;9xRPDke?q_rzjBhW}KRe^j-9IXT|JwGzw7wTbd=LYw4p9mz`lEufoVU zmz+@)xUJP~=C#p-1{m$O%h)!>NQd*232NaXS8npQ|)i25MTza?Ogrrl@HM` zVAVcHDx{TRC6nmwRr%fc&AUvzBR618%H@j2X|8VoOI&ImYXJ~xt%}sh+VTxcK!B^wdx|{@ zBY4E(t=K&cNW`5q-w55HWtngQ27|fhua!(e@8H>C(i3;nyW8+4!oj&@@5E!f7g3F0 z^$qRg-!bMP2z>|CHBkJ!@9iNq?8@Dx&xSr<GgoW)y+`!z9?P$DSFeuetGBwel$XG zDRW@G$~+A7rS=8Gy&RXU;0Xq4J^v%glNcw5_Z*KU&<6H98|+~dOSkW__s0IfT}LT6 z3Xf?Y#y$AGU@12IrF&1)o-~#I!**5g_y;a@nWlg8VGwetStV%u{KJe%cj}d%@`Zhw ziM}Bd);cEl=t*??^5L|LIQ16mS)977t7~;?TU#4YNyIzx!Y@zw9~m08o~j$7Wkr*P zcKwbck?=Qo&O%R*(veNxnP*yJfbS~2vkUJ@4!rgDQo$%&qFZ0ptvjS{1!nh`jCL~` zz;1Md(&FH$M~=rB=T1enh0^%ux@XHp-cZXhA_-dz9U+a;hE=A{I|c`1gK!_<82H3P^W{nabSabxQSb#9+SM$((@{Iga-oD!6=om`IAMirI10{$ zrGy@ay2Bb={-j9Xi&6I(i!&sG!JRmN>SDRt+HKY#z+aBN>dQD+@pv;sLN*NqQ`y7> zn;gcu`p~+zu|v>QAnkatOc}Oq^7M%J-$iop7En6+OyJV*Q4g zcYdvGrcMno+@VN4>FK>km6!_*BomCG?#X_|ru(fMV5WM?$?qQ+;VA zgt%e*=oSSNo;T>e2BP$p9;lCSfKyCyKpm`^C)WqGZ zHj#o)FbS<+%4R;`Tg3*!$lfisb3}awB=W7k-E{ny$QLG>9%gYu@Y0~=${zaxOs8Pu z$EbG|ed@D=;d%E;vofb?+%4)}))$W?e3+_XvBytjiRn~&P%}q&(3yHvdDY@2(Dm~% z&VH~;F)5!`!W>P1V@9Lrvd7zu+|_x>kp(`#FE?<5R_OP>#wo-#w%winq6XmP=C zHGVh$eGF@&*V9YW3*f6^{`|JViOgF1@u?5m3r8t4W(Oz2Y>QhzJSg%ji%YnL2KRQ@U|9@KF}xqAE*PMeLMfAqQ_{GLNTkaw( z2q}g#7ANg87L<0@X3!UCM({vLnsQ}8ea0&(PXULC9cD*Q;Dn|Wk4)`wy?wP7V`7{? zuFoTm!??m^CIW~iJf2-(iv0zT3I2x1<`hl#eB%Oyr7OJgs!g|0oF<>o|JvGNnfu&b zn^>YU&Q+1>VL&Jnw*3$-{h2-Q0(pC@Nt%1k(9p*);{XlW+WP}ocX5*bZ1w$q+vSWx zk~nSi!1<@F@GSBHzdj3$1usq=6omP4afyt83+)(O_m*K>gyUU3Qud(@gif8HoEa0g zsrh)m+sd*_ngnqhE{MUtZ$!(M6)hK^l5(P?`V8)d{s{E>E^dU3!H=76XP~UY2uR!P zI0u9hFK+%4O2Bpk*g5+?BSGlwhdgJshld+KEh|3>^cw-WYAHBzru5%%eAZgeEV5udr~9aXXN1Y#D)2Jm<=D6W zN5r?v;p2=x;xGy4U_fi&z}^MnLfND?Luvfn?fTNURfGoY z7e&TQ9miTs%pUs{GUgjl;xV^FHY9{6(~x>&VaSXG9}dI9r*{V^8;FSZO&XtzD%{LL z9_r=qhfq3}t#iC`?u`Y9wqv_H#&kd}P67=vo_Q&TBxurx%{n3ki5mY3&ePd3sQ!JC zVjer&1=EP@VYSjM|M&}Xl%!`sjHt+xXV^~UuE^SMe#*I$h2wme+q@QonECm{xvPhZ zrY!~*e+JKCIwkVeoY_gBnA5r1ZMIBTk8*W%tPaO+Ij%|3J~%F6j|nIo=k7GlZf+XT zxB#m*^xMh-{li#i;x1W3cXb&{h^3#S9;2;;^~ zj(_=1MR7Qef%g``u|r z>yV15Y~lFaqBG1;FI?<`tF7i^zQ2dQHtY+1b;!-llxNY>Gpk5Z^R)G=<6Z^sFS2{I zUpFHj5tz{s6U`$|yR-h)Evtv@@Vj5u-@Cb{^>WSm?Kt(F_Zi;$lz@}pypiTmjEoeF zOq~-#^)Kj{@BQG{oLzYi?Uc2Vp^J;!qd)TmmT&bT%!<;Y4hUX5bhTWB{`vz;ejjQM z-~ImSn=5SR9?4~}f4ECdxBs%=(?5{yt$d{?HHT+Lg<;th@P>ze@y>}tnmF|kz1|j` zKl=5Fs#*mKtLH@HN;t1!znxbwmgC&N8q00#s92vz$k32(Qd!MgfjuAC0`6u#z!smT z&ww$I+SAuBKFpd(PNw2}PUcn^N44HmPx0%3yhd`d(OLm*3Vo9RTtU5BIvbyR7Jm`zwhG>ii~{TPDT;AZy78uEW!< zgY(1u$20U8(vcJQS0f+t2Dx+#uzY1XcLD8dS{wlL5BRY}1IvE|aJOQ&3~V6Z(W4JO zzg`VU(P2L_(fOz*VXdQzNFiUTzW#TDRa{}12sW?)~#BfC?G8%>ee z2j>_@8vg-9{O;kCqPHXN>&s?1{{9>Pc5u zgxye}yl4iC@ISn$7nJUKuFeLcHpR1$8dhYT4*oen@0?}gVzQO0Bksz6$0p^p1OKs> zhow^-{$~(tQ1DQ;=~*|9c%iX&xYKEm^OZ?zjarSjxKGd6?nRjZb}Ba;4!k_fH?{)Kg{kUtsxCDfCIkBP6Zb@pD@BOx?9NGYy_AJs$(%<`B~rm5t!r z)#-kDuhZr}(Ad&?7{Z1vBGY%_bQ&&$HrqKLDOs2PJ4g~6s|aU%;g)eL(bo5m zUK!@A$oh|m$E)@~+d-WAeM=279t4s$F>NQ7GBNzJ(2Hc~pJCV!`~I)3Eg-(_kr1bU zzzeLwkgucxe*eSLe!n+APBaI4w<3y|xbngiuK!;E1qwMcvvO~0mJL}*?8f=NcH6^Q z{JVdyLH#vweEw+c)>z`|)vHcG@L(z46S@niyRlrqyw{Ve?Ig{FrWO*N2b&cE90PYj z8H-e&uhh0KBs8C>qD4X`=|Hem_}^SlDZ-_gnLLhRzd^3kT)X@+fA{zQYdQ&FN|VNIcP2Wt;&o7oZcF7a zXS&V?HU;0zyuJUD|04Q=tV?v#zg-k=mPJ6zpHr&$4;@kCC6R>T=Hwq}M@jnPe1E-CVOfFaBEH>@hU|%`U0I ze%+v959ubU*5gY^_-oG3Hk=BwytKc0;84gUyh#&q*$z$IV}KzcpYYTHkx{WSgJxADCx+GjQ~Y{)7e}1aF50`O)-U2PiCr? zNu-Grx$UFQXEuwGlR{PEy&a%3A_UaU4j6xVE5gG<(Y0)#XU~OBsdem1x zxv7b+D~bFV_dG@cK9<_4D4NF)Eh^SEEMtu30BuudB>R%6UIgF?JFI)xW`_y zdRWn=XG}q5Y!{EI=?A1nUB=9j?`yz|#k%w3(nY}3rU66$Z{mK0iW700TrRcdHDn{! z-461%LO31Dd-+xgmSG*NyOkVUkn%#_Lg{dPdXQ;nq(}^|_M8G^%-!$_jWj)CVq45n zN1bY5E~^nfq%XAl+P|{ce4zSmMWm=PT4bvbeyo8#sm;D`dTW9c3qyHG(dzQMY{H?P zt*50?bH%bBku22SUn1S*lmZ~%-@))=A=1JF9!$r`mz_L&?m-$R_&f@iG0Ft@5@*Cw%q8VO{utb*;h4s$*{^~qOt*{ za8KVoW9EG6rwvfuzkUd^{d?@_JW#^i^&$90Fc0+OdVdG#8 zR>|Z}d7)D`+rTDU6^eZb$XKS${Qh`JcvcPn8c2HX?^AafP@OG`@*ACRg*vHAAI3ZV zX|B72L+MGV%hNw;xJ$-&^~RMKO7|zW)v#n%COs|igl8M*3yTfglV%+@M<|lLeMA{b zz;oQIep&v%BpMbg5CI9mQOHgvR~w`P!*4Izab&?;E}jgO^jw$ruoJ0U_w~xhYF12! zY_L@(Y!*V{og)?uDWJEZ4;)PwkWim9&(P>itN>DPXorKTf00%j$poiPYAQGag zxuY2*;gdYy$N^jl0t-~gek!dat^58|I|Bz*af*^e)w1fSO`wcZMZo7cK4xlwU))Fu z_pdqi@8LBBBR}V71e1cO@(0uygq~$m!QTI`#NBe~XgO!8bu)RdXKEois=lksh)!N# zKgu^MJ*nS5l0^mx6{0`aBtmuKt-se@bjNc9xK$-j3jir2HSEmGS`KtiwO>vIu=Moh zd;LnwSi-Pcwnh9;J?3s##z{6D`^1iE`o;yIavaHxB6rr6mX|sWg5b7l53zLXX?hHB z8Gn@9|30s`C>N9wUiW;w6ax)WF~)y|U`s*`(7|YKxd_he>^?lrqQp>$>*Pp}1p(54 zYvIsnC2)f}<$J8X%ob!t+byWdQgE?1&O#D{N>)ih1b9jJwv`9J@-b5}d-cG6JbIN0 z_1*wQ?E4YBZbP`}RN7!z-~VD*e^TNANhXoC1#tiCll2;#fNQ4ejZ=EnvHEHytu~^s z*erAQ-b9}4?TxliXMCI_HbVU42`=Z~)`V`6AFgFbR8&XAHfv^<77z;O{N-lC7o?jq zbv}lcu~0u>7^nH=iY!~GWmNG-$D~9G*wHID{~YxruPk1MymEKQ%9|9iTAqWBH>tS% zn7AetStK?>e(%UH-^q&JztU)u`PY;^l6}8^U4B(%u~VGeSmkPK!UPY732^16Ki-hv zGEShxX@NN{%l}%p0xR-`vd_XVdhax9B2(?{<~@=!ZHbr==FZ#^yPi=SH{-U)H6gE8 ztB2OQPq7ZHFuq1|h;ZyXpJzTLnxH;9l53?S%^j9^gf@2UCTjkDgHYzYOP<5$XKLw= z@8|0ZihJJ?n|7c=b&QNTL6T6mmmPRFz_cts#YbR85SGHvS?O3H%GJkoE7t*nxAzCL z7jlOzxb5|NMm`6Bv7WPH*01P=Lr~g28=0@2vb@M4&g@Kn5-C)Hxoof39E7qY$op*C zefa3k8j|^mmAA;2YDGgMA)sN{(hJ70@<|I^rwJSjlGlR-PWuu)0qD8}GCP_~yhk4E zrFR+dit!6MV7cxbMVp`A_uY}%#_?ctM{a*oZY#+igaZ|i5-R)f14j4tQzLYP4r`l- zccVYQ;0W#%=r2WdAu6MkCwpBgoOWpqHBX%Dzcx;EH7hWZ>hn1+%4rh$LSF5~vxW`> zY$jt((PcZK(VJ84`k@D6Ik1D>qTU6FB%xwQGbcJq(BqmVy_$ zb#oUub)Cu1?@1R3V^ZjoxLH3>Aw~?)@tpTpYjtkRlUj&sRxVAeDmKKbu(S#-97Y|! zG;T|WVQ8k|;<(NG-Vj4pV)0g~Z7n+>QM6UwQcS0)VBdVS@kbj=rl0h152g8b6R1fI z2lEGav!frWc(<(s8)##t&wdc3CEG05iz~rPs39*R2@WF$g^$_qnCM%$x~$^%XjRO9 z;Q?a-eD67V$>BU#wAk>2dGU4393szl35{uiEAHF;kT`dvettLUG{1F~K~-J0-l>Fo z1dZr^KHrD&Yo~d#K_E}{vEQE1czz~*o#{Oe*}cha?uwS5HAh->g#B-^p?TAcp#)qj z;_ps!AEZwafpkO(lAS{`W}udP4$QaG!re%+gcyLDn$ggE++rfzr;z^a!HY$GLcD-m z4sjs3VDih}^U3SB?MbTyLZcx+-UE7B1NMv0uz#`_Z4f(m0YfOSdHh~9ZC}DWML|9o zFWqOaxFN}frm z2?(|FOu~SuZQCyA&wb6fdNczMUgFmNo5X_9dUAbjd}(f&YLv>;YQe0n10LB8dm4u& z4^S6Zw0DSSxh)dBJrP_p6a94v2#8(+$t7jjr22<0pg8=9_mc)4$OO-N>7#J&Pa$W2 ze;=m%*#*Px2K-9S-B_B2rxo_{^Zn7EvRzB9mF9>EK=@fSun|$HQiDR(W|6je5n>Z)I=^^A{tX66S_^3Du^b3JylN5J=S5f< z#Kiq54=&ew5R%$&iS%U>V;M^)DP=noWZ3%EVwfj` zdu@z|G+%062aFz#Ad9~cejrOJ@pH)>3_}i*M%RG`<;zvz0hdlhE<@vi`rwpc2Pg+2jJ;N=8tS*Gu7>^6Jf4|1yKg!;fwHRKmPMR zfXiSFXtDcGaKcvbcBx7zP)vOaKHR)A{PY99R_dC+dtdC0DkzR!Q9!)x5-DqlDwb5+ zUG|bQw~6!bzu~j}!v?JDSD^O0t`|ZGSxnGUd--KLY4&crFqUFhyE@xx)#8h=2hWOuH zT8i1G9qP>>c+up3ewRgoA{WhQrrFyPmT@cR%n`;ptMprI!U3)_{h+7q;W!y2voQPI zm!VB}=_#-!O*>K;A^*mBH2alF8Fr`QHqE78Z29n)KT%8CFfyF$4$bO!hfGaPMKa}P zXP5U_%34c*%XErh@6E3~a7D4!@VLvQ{hQ9e<~lb*{%7LVPb#D(SlvWr&{vyY%FL&} zFx#xFE|5HyAJO{4-R!Pam$Rz5UHh8z6qSXU;g{j99);lxGoCV1REKTa_Ri0G82B%A zoU1Q%LPIO^Ymms?;YEI8kvFy(5m0J2$L4O_`;F_4Szz=D6^Xvp73@^M!8g(Ho%Go!>HD!J7T#iP@GTvP%NYZ>;X$ z*j=SX`vN7`LB1Cef=!w5jfTYeqr_s@9T%d5uVP;=4T@~J94K9e9YQSWXV9+imgdU1 zw~`dh^u-(lX!7v6*>9scfzi<$2L6@>rDw}_5(6V^SkV>hE)URRxlTY4!g76+f%tI> z?ncbf#kOH9R@K3^pGkloTcwz$sCB;KUsHUXW*d9xetz>6@p37cI|tEs?05MKPTU}S zvu$`EzPhx?Cvf0Q9Hbf2&AHm0;RXvq&lzK;<=4;U_55O6pi*R4KaeoJV1OImt?*sQ z4ykF6orgxmAT$2Kyi1VCZIAO}3fO?%5H-7R)d28i>I3HXzWB;OYVc);%6b8Vef$q8 z>(WZ9L-(a$cyh!$5V3vVildZ6al8N0ieNQ#c`Bc8*gy()U4H}V53`Yz=_Bi_bOGhP z>Z>5GL$wvfXwZX$bt|~}|`Z9dMX){>@AN*a(o&)$jZ%&%W4-VOc^4!%=^{TJlk-^4(XArCR3nMh$G= zC9w*WnaR;qaEz}kALAdY9|ZsWA^B*t_$A=M7Z1;3D~;18u&sY=rSXe614k>eMG#=g zyYlkOR*Q`rDh~XcQwKQ((2pXpqP>WS>?k9&xcj%qeQ}J>3M##z6;5#P;rD)3(EQ0v z{n!uCNM!vXY4gW*X`$x~;s*TGr-X`47n{-&qlZuL-t<$IZm~Pa(%}&XNz^Y_vVGAm z{^*Snh^kI1fs+s=s4&~8@Q4{}(Ct=^zUrXlz@AY#MdQn}vV$}hq>!2I@cjxcM za_15ldh%~g$Di_23NrA#A;Dlw_-g*mO@YJnas)|kErlAf>3NH0_TSyipHfc@YMa2A zTFU1wwi@_fcI5kIgJi&RuNT;ue|b-q+f1o!`&9F9&)@g`K-}TKvLJuBRLQ@%^Zy47 zf%Vtx3!E6#lx<$^&2=+$XAVsr79+jvwRXHZx{1&1U5Bu>bm{6P{{)c!fg;uI%}l%_ zBO@ZRm#nRWIaNX%-TbLpPtpR%&8Z{sPDRD2K&r)h4e5L2CqbdhWpxd%)L5l-js#{s z$qg&FI#N!qS$25m>7Y(iOup0Q{CQDKxnfdBtQWC*bfob-3 z9+HD|z3H50Gl=6uG=1QBI~2Lijm2fNtQ>-wUEf*)a6?FTvWJ0Y5JnEwg*BYv=t1Df z<6Yy>#^O9KPy0UN?Vf0H_>p4-y8TYZo!Gakkp8v6V9&yJWk^qLRL)Pfxmc>x-<5s%xiee^+qcgZr7%#Z9FI3sErs6 z4MflnCiovea*K8`O!DG>1)!7jRhTWxBWsF7W*&(pJgo0FZP^DSN7c`rI`Lq6!F&MA zdU(D5+kY72`T(4()EckYZ+Yqs)z?3PEM5!XH(48oW6aOgwPBW?ekO%YPxb*qIQ3F; zAb8q+wkPoHgGRVt^AK`ntygUbLh{R%o*|9^5cHr*TAV6kyQyyXDlfo|JgUj|wA&FI zy&fhSEt1op1bW~w-Ls!6a{+74ZG8a!fWg3v$XU~DhjDp{2cOhPom`COj;XVj~VCbfgp@g*JXwB zFr8a!^-w^ryA~IuL!Tb`=`7qNkLk;1-Ih5ARK@kdR;#>LP_c8I?W--zQQ}-_5?_%7 z6-ki8itaT__6iS0xejMz=>4=qP)0}jF8Klmfkj>lY^PeR7^x(%)UH21+bx%A|idK=(Ib?bVMy z{Hog6qRAmL!l` z36#B=(k+KpH0|8|9Oqt+AaIiQSdp9POZA+)G`Qsb=E&HG^vij={tZzZe&G5!N zDTO90h%6ZNzG6EE8v0KqYD!L>2?^w%Iuh>uig6&{s@x{yQgx)7(BmLhW#gHb-JaB8 zj&tOx>SkqyB2|gZdjrXpiJ>LAr8OY8c45Zn&2$~uo_{|OfW-$9vsvhsE}T@K$cGpu zpbQuukfa6`IdEZLt`ORYH8Ea(g8KBdiLqpA!u(NghTxrI_&9A4+*d`tAFeytun?%g zf;BiC6ME8IK^@YFA&wmH&)im-yz=!~S%~BebT-r;eeelx@fv{@Zy@Hg z3(Nt-Z~HmCP1RJV|8my0;kZ=K-k==&0SDRh_)sE;x^4PB+igeX0(2K9aFOtRBl zXgX%}r3!vVdr1^%>J&f{bXu)dFkb5GgmjCUzqNu)De=p&nI^F1KftL|gU0)eed;ai5)t>CCnmu#D9=+PLC-meqS~$)Lr@hcdbl$iT!^bHhV)$HJUC;5S z+$^ILIRfM462DPSyHW!#o9*IwOIA!zS+LWP=)qQUUIy6rXu6uV4(oA&q zXTR#JJgCdC8A`Fp&hL9;fm2V}ZHXIoBN0?>s`F75x*Xi)^R)B(NpI=>B~D#3JfZ>} zfsCrU`CsCMA`V{)AI^k%&z}g5kKOjqm7cpvtvEN4UJoPdyG(8ke)_2@MN?;(D7|Ql zxo0vS$4N*^ert#pF!Bh2oE>oSk7n`IsFY!VMBjn@ijev=}EGw??mc@iJFIF z9H3fpIp=Cq+(LL z3ne*2U>QmyCPSiylqE|!)Vr|#12oZ(~9U4vf@%;>HAU zNGpomY(HB#b?$<3rfQLwNa<-2Bh8h`AB)xFD+I94Mo?bcA9$?4RPlaVG?^q98XhBz zk)$+gE9CJ)i2!{&qt0`V@SC>#Lc@t;%fIi)efW5$uC9Q* z%}dP;3Mh{cw1jnwKg|^ZETd^#{Z*2xk?wK`s(aUAs+K7EtckRv;1;DbOUH9!={iDoJzur^|sy*MQKN$(G3bce1|E^IFU)t zuyaS_N2p*i9q#KXBlJW_&aM(e4_C?6?9w$UP0Jp)c<)Z@xJ@Ic_*ir(YH{7 zsmT9IPk#Rd8BNifnvYuTu;%z7{jD>-1z&LZL=S!e$^g2|$aRFLl-czeUBVUNonlgn zlWY({nFpdi!i#i;Gl@V4jB#6g!K<@np{?GT&`|I_H1tY;sz)rH(!jSwY!$FDK9bk4 zx0jG1 z<_5Wy)x8V-go}?k3DjwsUMjOm!SgnH$-{F`)I)LVQqUVjiKzjdU}B8l@VMGt%FsKE znDY^*?lK+FO6s+{#pkXbU>zmjv};l)0%;@MQ0DSz6V++(G)Zc4hc781M$WH; zG+tOh2z!glEFPXLFLvZtUc}{Ja|8y=-rn4@545!Eg5$9YjgVKP9rCq=B&UF3_Vers z%is~G!A>5PLXX}NQc2U?3vcl@#_hJv!p?MOW@)rsvQoRI zLUyW|cT6zJ;fw0&Ph+nPc`G&3$BORDTV2LXFFek2h42b@%!&i;alv32x zUc}{L9ayFBb}xEbJ+UJEp@o!Pb3o75v&Vo}t{I*xfG%K+)vt zx1vd2PEMLjZknEx&A_<9Y)e=m%6Wd*LlN7tlydYy%oQJB25rOTO#Vx4zTRUG-UA5L z+kZ}#9xR2-%5{w#?$Aty9yG-s=J=g%q^Vw=Ck}yqn7+@vo=aw(Y_Ub^m<%T*0T!kG zi2g+792cnhn$#vaZH$94qZv=5Mcuyi8X6uisadY)Xt@L}IzGb~8KqSR^0aF9WKF6q zz1L?=;9y)vRPArx$*!b<49beTSL+VKDZRAIaQmiezK+V#i6MeCS=0KEt~zo%;|jiQ`yJEs%VHUmy*hGLAHFD56XihX^)Z55N>`}C(C#-t9~dACtwG$3G&69qW`yIZ7gG;+ zG1s4xEg=F1bMu~F=C*K8OBl<=<=Vkrs#p&Kr=_vmQ}W<~G`q>2m;-4k^Jv6!9D4wC z-a8Gqg&Zl{$Kq~=v$5VFKU}|O1!*M-oWoruohhfEd_!V%!Z$5npSXNyyy2~?{r zSiYA}C+P;2XIo+eFd-4hyqn3i!+J6@V(`O6DuwOLAXd5WyGqS#1NL6n)o*ukvCGSd z+Nb8)!oBwN-MrKDI1Ps2HoRunYA`y80^+*5A@EOm8@{O- zydppwwmx|1)Puh*s&Y`BhI%5%!a;-i*?zHK1UQLA<18I-Lo?}r`K*27e#nxC9u+jSIA|E}vW7@PDX<@x$i~chxx4FJSm@JX-$|;na@c1fr@2tnwu$l2_ zW5Uc>rScU$WN;CT__jiUyBQ{?Xj1QI-UJdiI!4P0CTJ9(3H@U%cATQH zx|3ftxFF(3IPq^2S5mQlf{D<*x4iGH0)n*8k~IaY&%yjq8|c8H4z>9hEohK1G1hzH zOAWjUvf9}7z=NZMAEV=9UQG0Q?nGu{FShvzNh6cSBSrf{M;Feljh=AEH@HgRN$Hph z2o;1#wd9V454AxHRkX!-ZmLMV{Mzo+S0gd{O!pnYhzz9NUah6`gKy#iRCH{C&&1Hc zc7Fk zRG~u|&Kg+=-V@r%fi9>uBIeF{CtyT}pGHT!|65ZZh*`{>iVl z>V^ArJ010_+2tvXa@z-1mtj-Kp)8nb9-;LTR^XRzq_%TbDQ;fj2Vj|yN;tfIx`aSm zSO+g+Ulh<&4{$dI5Kv#N^dbK_RaLq`GYjPOf_w(WUn=XT+kdv- zz^U^2blz9pbEm9t!H(4;HGZvqB$K&_TwD|GfUzQLG2@4P;guY>eD=EV_CW})rM;%K zXr}DCj369HpNMJ6NAeWh(HOx408qxDk7#eKJ;GS|KupY_64&31x`r-Rs>?^(0)TJ< za$P7Y8s=3Y;B}JjJp+~`A78z%rZ=?Z;59OYo3ls;{J0+y7BVCEY(r`}OJ4`bctr4A z`obbL5$}e7A$xCw40Oy4hPH6W(l*@?I0!%M8LU2tWciTE5HGmt!D1)35~f4K1N4YmY&Y5Z(1|7SbkWa=wE^4W zfpcP??WvWp)5dl~rIQa44kf*jU4-f$(f!VGTJ4Q_Lf1Z(m-~mhppAYbOvXfY=l7Hn zp=GVoaya^bczesZD7W?vR1hUZ8WojpP*6Y=i9u;lLb_2}N2VRbjSPd{hssxbiQoIpL?EJ&suk0_qFc3Yh}r!=lTb88=Iox{D_L1 z3BhUlo*pqe_KQt-j^+WLX>bA36aO8sylBuCLXk`p^b=QC%b?04gKSa}S2!%$-ue`a zgWx`9I3JmLe-E$mDrH=U4AM4Ax-bT09Y@P$RTd>d-ISUbXYX{|r@+kwgL4Z8F4p(h zl5YJkK;;6G*XN6(HYw2mDM|^w&G|o2IGlZ|dBPaz>d3t3aWrU@89OrpdX-CO1do0C zTGJwByc_+&?&xu%{-CAf)D;0kguoxP)EOJzX5zRutIJF$@+T`7TBzA4 z5(G6(x@z?nu#VAQ=*)jIuM?{0{n7 z%Hs5m=8c=}52?G(Bd8iW4=O(?&y4a)F+KS+v6m`4+#Azu_V9RNXZbUpkw`ux6zVFQ zB;03g+!bJ7tFjtF|CU z47w+9F8(U;+~G5Xv)vHb^lbh;W0<^T83SlBecH3Kp{4bD$@Cw0cG|XBQ_u*R(XZ!I zZaQ8@Q1X=PZ&i$Y97c;rl1i2rf%_ZHcb}Or_+IYVv(`!qd1|C|pr8)AD{ju85PKe+ihGd zIN-hO_|k(S^W`hTqN$X?_G;a>=%hMDP@a>T#iDN)gD#>s5`-);YHyi6lJeX=)q30) zOCNw1``t_})gj?Bw77B=?C^B;I|qg%nZD5p`UkqATuzw$k87Xhd01}R^+^@D18Qix z)~;Fn;>ng2oL>NC?6{c0{Nxvmnt*C|I()yC^^N1l8c7eBR{`>4?J@E5-siz;uHs0Q zR6^4ntd02ar2pvThvk-$H-yh8htcTW>`_>aD(R;FFd)$dHPuuBIXJ@Hl-sd9?tbD# z<{J8g&BPo2`K6g5^~0B|Uxp3Rei$C?$S+_wu$ zuM|7&#Pd&^bQS?5mN)EEV%A!hhipp)ke_tnN~g*qa6btcpv1U|xNSqvWu1>(th~YKwhQS(YzXHz%zZPfi2B6;iEA1cl&_fj-35@!4T`A86;h=}y z{LIJrg9IKo@6KAw+^u97BHuk#nIRxujux*N=0EADyFxz#pW)mcc*Y2Rlv zQH(u5fkY$ZZH{=lYb!R6#aH7yGFGlNEUztJtAB@}WvQ5WS*yc)l*pW8h*3I4cRNw? zBEoRq?uqJM?F12PjZGHNU=^H=rqN=B5|E_MWSFXjzoC98*Uga!sb!Eb3Bn8b+-4Lw zjpZhEB4CGhTAXitHd_J`uU)Q?>rNSM3;$ttI=I1t;O5pIHLN&|39e<*NBWrJfLw_u zUKU(5fDFd^Q{cKRB~r~cv(P6Xx+mLB@sT~5=!2$OWCmBJ$V^~8)u*%^NB6aAgf?2R zXk(h+RAMhoJq33gQ>AG`A!=x7q{WzH+6=;E(Xa$6PJwU&l*Ig50X+kXJfZ$r^gWxv zCY32`EJk*2*ARwECp=GAt2$Gc+_EsD)$Sw{I-LSr-cqt`mb)1_N;UECMk=^Zu=2jZE;qJ*FhvE=8zGvB8 z-PFt@W!bF zczhi2ASMq>d4RbMgr26tczmy+KBHelD&H#LmGXIO%pgelcQ3NXxQ~5yBz)$^Gm=^-wC#?KK{lD4`Kr_&(kH)>D!O7#)lCQ%0NA=fW;Bx zqiwm3|}RDmbW$CQXDtL2a?#gwuGgd%8fECX1PbO`w}}(s5L<tPO)Msec6T}2%VhW8~ ziE56b^)dxPk>}G=(4t-MK6`PC-jTx_Dd0mN)vCRV7jV1-XHUnXQrGZ6MM_T_>qD2EX`7tANq$RoR4 z-5?#$He2AVnq@EKYVHxiBV!FjE};_7VCQ6Oev>d)P`x4o--M!+Jh^Q?3ZtvlSY7P8q3u(6H`=wy1rG`XWT0}u2XAfUA&dG7bf_!@^uT1 z2d@=ZqNi=~g&ef%n&bCBONc{q?=RBY>nlJ5K%Ak5ql+zQjn4!5f^dS8Y&@tm_)3&< zvqc{L$uuSMTA@W;3k@caklhR1T@+U;euRxpf+r2AiFtK1T}ZDONp%u4dh9RJuxsB= z;?Vp49mbQei|nKzh@#yRJq%TywRtNWOi)tQgdRdIU#kIa%eysptJjT zlkem;w2RT~*<_x?OG*QCNRdANtssl2lkVc0nc;TOqqicz?qDDa;RLRA49^-G^2a?L zz3Z1L5O1h6hc^mMashLU*kq`;h#6h_Y>tYhP|LR~_<(;J)c4Tjs&wW6Np0FrrwYKK zZsNED3JVj-rhg2uXJ#PFe}FN|GoSMIy6bHMB5#k*la_w8(`HUqNB*bant2)A0tJA3 z6(Aeb!k|BsYMSRjqg)CJ03%<``|!Nro+Eh*yKp6WD(2pvId?d)JegiDMih zMY25axKMJnR1qli;1EDwf*FLt-@if#O;Z#A)-50ah{I*73;B)hnF+pk56)5qOv>{( zxQ)5%E>{XSfOEI;lP~<54(9y=xZc$p5WEETk;LpGNRwt1EL1p3d_?`AFPT>@lfK_ROU@qcQW{XPt@k@G||P0+rkg) zywB{kd??B_2Hn8?RT~*e6s1#X4nPln-*aG3!EFS3OTUpIsB-@~ZJ-^V9q+hoO&I5dj}D43F6Ip3EN5x3Y(h_a9 zAfLJrS6i_QDZ4tb{vsl+{`6&qD(E7crWW}9T&&5i_iau%9_^4o1ri|MV3a^_xWqF6 zUGzZ(Fj-;1EDt`1-NZx!Fjns%O+oRC;JD6U-v{UAFcZNBsw&VWomSd!XTgMSNxBTs zZdr7$Y@HS9TG{!g>dGn!37|IP{5Q23UqAhN6@GU#%^1ES90-oqP0-y!|B(1&%}cbIWp@$8p6w$B^Tf2*|5nKYbgS3* z4YeTl?Iq}H5Evh(g@3)OEr@Sgg+cWA!&cT(yC`P;GnV%=00dL;uKnH(lJ_7~^Vb4D zUrGv|DF`ne;M)+b103s?YxLBo_b>n>7wUAE`L$&R7!`ukJ-c)s+B4A0QpQLEm4EDkB5jV zg&JytUE&1Op}|rB$S`{qtRSZBa~G}1y+5ETVMI2dUEscKE(OykE|(bqzzneM2V^I$ zVjtUe|_f{yal!)7I2akF976}AKc~u{U6KUu+ZQ+1B}d>G2`qhZs{c| z2mV^>a2PKH_Qo5E5*zBlzP1B-V+;HnJO@DL3u0i?AX*!_r^kzBmfunit|>e(gUT4U zK^cP&U{+@BCf`4RGTHZoUJ*f1%T0M&u@7B6m{w!QD1bY-FfmuNq+cXDK9r{!K2{kx zoaf5dbPb>pD^IfV>7n`<7pRYcx|9~+U3C2x2Plbm=LfH)4IyI`|ACAtUG@VwIB3LL zfD<-mB=N?U<2Qj${w~=J_1QXTw_i7 zO(Qk~xPI>&&8b(Swm_x`2 zlqnadv8z;q&)y3aZ+gqKe>_g{pABz75Tsn<9pA>k+$J%d)mnHAqld=a0IX!JN23UZ zes$yHGe6LNL)39$jCEf}J53B|rtgi#WYF;X=NBvC2-_cI3nQa{Z~=HXvr=3)Tw*Uc zd7Q>;r}DR7$S@)%O7E=}4PzW-iNOhp;7IpNVgEX(GZr456WdpchUNuS7bDQ1r@M0u zNvJS*VIeFIb7ITilx!^q15X z(v=KLh!={(jDlG|Y$fv^+Ly}pIVvVf#dpU}=suyBuFaHZ21g~sz^t>(D zz$DMTD&Y7_)Ba|wRN9f-g;yC>e`9z0_jAjjhBBCd+if2TpvL$S{O=wE;6^$wM!@tU zl^(#;yq!T8f3h4S&t=>95NLJCC+OSvWC=_=hz1j{_~-WDjD0TsJ-<#iGKdFoB_X?R z1o763Grnj5-+Bo$>;%SO*ydXtsi9bc5FZ4h#keRjS2jh}Q|YowkJ_t7G~3Eq{^8kOTiM7|C`- z?fk;LqT6P|z2Fpts&X!@bboH{?zWr{n)J^{qy(>xJ$#ulzSvu#Uc+8fKC0)sJJPjy z@SNCoxdT{QXA+GMmN|r1915j~`36pj^CbajeEqS1x1YcQ{kET}55Nonb>SCl#P{3c zOIu}V%QlA(499PnAp8(%gA5R4VroyzR`@HTcoRkHU zewM1&fVpuk`xH{Diko<{#9GedF?+YW<09xz?%_0+fR{?&Fq&c7t@ly^Oq{;Ua}@{p z3Vgg0-zunPTFjx3ayJFmDI6AK0gS2YxATBZGznEwO5gqpup^DfvyC0chmhOXD*9~t zcp{r<@Dp8{$~KpI6_~;NG^>J6nOctyf+T(61LrING|k_&cIS=|oZ~S+YQA+Oc;xr~ zcb^p~buh*^+g$=JCs|zEV0>OxZI6| zRwo*WCTXPV4WgLeE)0~*b2-5fY+PKNAeqz{z(L`q(C^n~>M1t5te7t7Jrx{61>J!G z{FGHRyUBRqRqQvQvq+XK=wSIq4mm{E0}wUhfnGLmJA4PgG(6Ba+w%D;HEhjsZk(+o zG4Gpvsp8i1(u)0}u1%rghM$1?6F~WdWSWAp8%Q)H=Rmqu)*1=0Sb@icnx^=A#fa{W zmpuwOvm}dcF1TxaS`f)J^q+N7^u3W(irx@r&=3dtUs3qLP^AZOQFf~!LbQ1EXNU}@ zv8d+xf(z=wfvohYfq;)dW&7E8vp-S6j38M9n|vQ|8CXG17;0H%}f8Zc`yWa~-j4L3M?Xn`>oocVAqWHdM zD1+=k<`@#5dvAgk&F+VB2h7N&zI(gCH+Eu5J13NU^nFXHTclgS6j`%(Ac9mtesZm zo1>}HTQacL@1C#VVR9nd^yD7-&(OiUZQ!)!9OhzN4U-jU&x;&Ue3|ojI>|ewur(aD zEPGyrb-HQE5q$Ku9Y2!aiESE?R{-1~e1Y5SJOd-vUXb}mxeT7#`> zZCFnJy7RkbbYEEC+A`|mo)+pw<~|EXJnwmQw%u^!2fM{m&0?t{4-T>VZmK(6`+I3p z+xX&%3))NdFMr(HRP3bUvCMe%$?Q>9MK^nE1-C9)fb3HGuIk|K!f=UQc`ijz(372U zk;^E0Zi<|%=X)d01;D~^I81p-;UsW7`48>8LhgwSUj%G%T49Z}jkG8b6nM+yI5g45 z(e~lHdE!`q`f*>Aujuja$b8i2$@y_94}p96gf6Oio2(p|eAFI|%YyfvnCG;rf#d{t zat~S2;@Xw{-E%s3?l{ZolpenO)``q+RsN~9v$Zg+v@s7d^Vm;Takw^V%JT;!WRj!m zo)c%eRvwLBo+%M-CvHbP!6;W!+G!+Sjns(&J=NWIm9$$7E=eRIm z)&>~*_pUI6;i))?-)qbMX;B$sQ5teRm*7B6X&M4|_ ziMtBr<9iCGDjk4~y_!h5Ar*KRR_SP>c<|M55OMBog4k2Gq=EFpPtV$YlT9#eX{EY8~%&Th6(C3mg#H$FT> zw~6?hSGA?E3oen)L*onBk~DI z$Z>gLxVLM1ESXWg!gi?k(~h{@MkNNhAu`8dRaiJHjs9iA=V3tty%jdT*j?$wFuL9f zkDMLt3Y0n(OTqYNrpS-(`n#a1aGL6B1(&~JV@a_(Pz1xiSu6ieJFMl0tlXwGn!+-5ONa@MFd4w{^cjxeh4%cfts~S!X};o&mo#pa3|{7Rh=JC-Sp=s z!i$bNL%cW};x?`qrS3v*a+1M7Vx>P5!XSDozk=T7*OW5^Si{a7NX;sY37*~f&+q)4 z8z45h5zXl5$!udkG+~H+vOB8ZL0vIMH)>Upob;k^aq~+rxzO&VLAr2aEECL3LyRs+ z(WdYe50w3drxa`h+uBIjBE43{4mW){XMynx;)^MvW=Ks`Pwx^|&>PyU7E5`W8;VnI z=^|B*s*cFEb7xW~F9jX7V&6%%2PlZm1?_)G7d_wECq9-!H+HmC35JSXk( zkd{Kz`$v+{6-D+uvns)%sfNG26^5--ioWh`)~^gVSh?7X2uf+ScO=fL*-p zQsz}&wEuzuV}zV59W&~VrrrVOuhe7U%Owu@whfEg!#Y-Mp^PJn$8PTQMazM{h*-8> zsf!+%B930xZOV<7mTc2$^0P=%cyU`sa~06B+l*>6QeJ2=u(Gx_%rjHGdvad>4yIzJ zWj|(O27cIn`#c`J2yOA3E zQA|&h46o&jG{>RO>XU_rUR7k?QgWQEV5^m35UFG&q5nvL{e<7;HHfFAiAAmjL>- zecsC1$e=Uny8`fig9M@JH}Av~Tzf-dP+RS8&}Vx`{L!5009DCSvz4<*<5k4-nQ1_kZ%hY;bON3EC(fOpjb#iKr>{pvT0^ znvPgMikM5f2TpK`c#3%9B9J3iY<}SkavC_^P^7x-`%jir8lN0S@@4bBT378wf>Atb zTB$0Ok5ty<-F8apNYeIiAH20`TRwO9JWLt8y(P|TXX&SBL%I3Kb}0+c zN~YqzY|Och!|<+bTW`^q3#1;{+EZvk?aGG}Z$+d=QT+*NB=0cP<*#?3c)_ui&2l*C zFt1Q)#UhP%K&M{z9ppaWR~+{2&UV*?v3imi%pquP8!zCAPTD|n&w4HXprHWU+m7u0 zEPYMV_VLb$gPzscp`HYxl1f8+%n}uEE`bC-^)xq1$3(uCi9{jnr_&ROb-X;ShxCl! z)$!Q}o=JaHFWXP=QZISwhjdCqJ8YnXM3t#mv|?aN8>Txodk*mtwH@=l0bmtO77uPxyAL}49ao_5&s*NWFesh*yn7t*Lx{jFqV zHIx{7H_o0{Ya}bXWsSGBH^&v*4gV2LEgqxwEa2+?bppD11+$o8^~d;rH`Kd_bC@yN z9%8p8hBZ1one%;CEZeOI)G|4u$A_vvy}m+zUtbQ5&uJH3x6|i$nWH|TQeJhV6IEPR z&uy6)tcFn;B`urXkfQxYR#c4QB!L&REOmR9dNj3=ZLl6)&st$|d$*je;Dt_K$+Iq3 zJV=N0ejvjZA#L5FA7ho@j|>r|amf@%`fiQP1OjasW^8Fsm`}QVg))daPERB+s)x*K zK6jUn!c6|&2A>OPQTdv`$W<&N&;R-$IlNy}=>dlp6*;Bh+m$Cjy3+?_Ib*qh(lz&2 z@;{zMxRz*`<&Eg$n=P3tk;>w0?Qp=~4hSoC4aA73V3?{98p*;~=S3KSBT(HC*InP`QY|C@Td>mu zni@a%SSY#bM~%9Dqy0fybk3#nD(hNJEz{1Nfcs0dvNM6G6;4aoh0*VC(J{$Ck#MzU zogt3i1PRRviBb>a$Nk7-v!jRT+c95C$KroS@Eq`^ajJknUd9=`j6ijv6y0MzW>Sv; zY@8`5n!ZdTE$Nj2Yjgf^6`SNe@=Ofu zaY@Rn_uUrrbMC~etC}$#^Gz4sPd~h=DbsDmQl#SBT7QsiddMW4xI-d}rpKiV4>>cX zz@wM%cLryf^>nl0vCrsn2+7Un=*Qj%CeRFqTp`<2d$%-vL-VSp&BBX5`!^edrTZny zYYMGpR$pg;I!9u%2qQdMiDZ{pe$w}N*UhYj#7fbMWYWhlx^l-ccc}5}v|z*WdUh#k z!Qt@uJTICy4=+G{c921h&w62vcgnoq6 zxC`f%)zMDNSSFX3-G{TAHnqoP+0LugatK+r$^hxA0H2czwUFGw0j-JUO36Jp#-sY5 zQH32N#L7p^I~Al8CZ4rpj&N4m18MaFIZ}A(Etisj(|9*B!Mpok;$0@<#TNP2A_m4o zwRBKrdAHy9{{==o!1?`0B7myn{XCwFox#dqBYcCZ_>=U_gEk$p9 z|C#??{>2ROn;Wbg;_OPZ#es&iedZ-h&rbx>o6n)HyNV;*dnT7&{s5VzX5;}nup4Uxwe4~D`^Tzv5|u4kgaW5$uZkJ-`pg<%DF*A z#Qu0Rl)W#B97M6{n^~*L-un%gadFyZQiuH=bhRwh3c^KNuB&U(s8w7a&a%P%Kz}&0 z^ul&1Hp7QS}rO^(VH ziQ~LKT#Ym2tlspC47eTIhrVBQef*P0p?qkMz|MD?sKc|l?&MeWl>@?E8 zR8t8LQfn4(y28xot19^qFO&O%z)JOq6YKHu4UUKG5AyV86-p~v+dox4$x)k)wAM3; zQ6Cjg5tvNY#s8$?eM4*!8}2}Jrq&S1y-m!M zZ)Y(qWy9GbSP#pK-p|SfS`F-S3J$_f@q0P8eiK#8Bujp4|l6ov0p~U2wQFX4m=D{qnKB%3tdYjPpalY+-r*1qH z(6ypFn-Mrj?`^V0@QS20_zY;P81d3Ve*{GWe`I{a>h5o&38IWjr}I<4ACN%|y#8!w zRE8ewm%NOl5}H#AX)z-RCzmyf$#LimaIt`oZN%DW31ey^z>8-IpP@gFf!?I_eo*dlYA)o|{A%?Jem;&rGDIp}-e*Y=4?wCA5q63i)QvIPSgKv(1NM zz}CQ@B{Y+dpr#h-F&S;S`xgHbqlpZFJ@suK8K}h{|5&<_xns8*@WE~=+}{1+D{cW& z#ZQtk3i2<8%jrP?cUN2`=p3QDBnT`P2;HGDX$tQbp6PxUlm?UW_!u!hiFDWziZURY zU`lHm$;YR|7(MR)atx(zkBqtg2XG>Kb%Rw8=Xr#(f08b^7Nr{pj)X}%0w@7TBud!y z>#i?|%&wVN-TwWPz~t2MlEC+;yhH`?jp#9r!J?(FV|dfoLD&K^XB}`Tw1W(OH6U|h zgzOW&&;D07k9}brG*fuy{#O~Ck@tFCG=X?CrgM{&r=_R;hi5ig;-sf=ap*`+k&hqN z;6b@~GxQj7iPV?GW8CR2y4X&5cwk`<{1>L~ymP_1~HqC6VI|Aoi~z%~R#N7a+v zUboYtK+zjQ0s-GR!vV=y(Dzs6|Q&1++L^J zkm6SED|$9*@9MYQBlHWb%Q`sn=cJ#!34Yc_%p%z^0QSu{L*+a@CYs~>on#4M*KfaM zU0=5f;+twisS1s;G~Konz-?zy7vFME!O{kZcFq-w7}L3H|U`b@2CJWkSa4dvT;|ow&aLkr^fw@3EJK;AWD=QjcfS4Rp&5*62g0S zo(shI#H1UnV0`_^t3S0*0U5KyNea&=CO!YKjtXc+mruKk7}fr=J6^J*mv^_kKR53* z)qco+lqS!ep@3g_a9M{&SqAH%^H|iFzgoH7Q}RPO2#;Y^PS0Sf7;~x zdtmO^uz-$|;ZR+sHvsMfLEm$ovD701M}iEvKk38Wq{pM`?l%Bd(5*CLU2NJOb_ifh z54CSa;vf(bzk-Kl3M}{E}hRj6Lo6lGpT=@dBnT`Sf`7ZEipE@>VUc8 zqq~_7Ou7p;#j=Q%{yE&b$Z7M_G&Sh2H1!|9aqpL-rBl2GU{#9izcxxS7--igEI=8M z0O1{H<3gpIK;YdGuHh*FRN|*XqEL?f$IB@$fc5c{c(r+ z=K?e9&kl+WPI{+V9N#OgkdN@}Ut=`JBynbF?nz6G0`&6kaLW0YrpvL)= zFv=~Ie~x`I?h4R)Lp;6~NT8)HD-2f+Y-2!{bRIH{2teZ2cHeNijLv&qkXP69nf4^PocM3tfaR>{2xsCcFU^t%1(*997@0P3MI_ zw3YgDI9xI)@_Ct-nc^mD^@wLXY3tQpUwVv2{QesjrGs>Qj?X+aDDt{z=5si$wVe@{ zD(FEOZCQW{8wITG#?808hhn2~H6Pet8<&@R_+s~XaH``x4M6qgMZ~|&^)S&N=8)PE zmOs31pHy9CEJugQmZjNgE`mDXcN0wO30vM@1vs98y+(`!fYx7O^$+acDIW9_N(U(& z0Z8dgS^q56AVoNTsxx3TXc-87ym*1#O2Vh~15MwcNW>20H&GYV_#uuINW7;Mfcpoo z!4g!5#8^)Kf!7L7VTx@IA=PeC@#w1Ch;?q%F8hX*o{O|!2ugfa^Cf(;K^-CR#5&&X z)AsU*5~1T|*93IU!RGPe1QAAi&t7vBF{6C68%fW4V($-{X>80Bnfli1*tfjg%xoa) z8%uc!Ed&ifyJ>jH21uTPBtozva5QHn$ljL$Ps37}RG>BOdF!aE*i0`mNw`?TFVxap z3)G79B>N}E=_U^63?&m#2(Z9Uxs^z~1&A62dkCDePJ57T3jHtr{ZbzcGFfgcc->7-xz{I^Lq6!6_3Ei3WyAq1lz*-*f=w&iYh7^FDsk?8leB zB<|G4h#DGKjJcVw`0bM;%v(-|nc_T5Rp_D{1DT$xcKIloo@WSqK0mVGZsC1p3tX0N z3WCWdnfISoc48%d+dGHWc^K!-0^ZEQRb=>s<64Hn<87h@yU%zow$q$_t^@7|aZxCa zv#3La_j-niKh5^1$&q_*F`~v(4Gk6e?MX_(XAb6-tU-A5pNq~~$rJxv-lIB#xAZ(ENpx(mncXuXndgAS|se zeU9+hZgzy|ra^CRss$YMmQY4E%zS>SAU(lN%>mQ@pe29pMUsv%Jn+#`*MdB6P_FjZ zYC;BifFF561##X&=X2f+5LxGLC+hJb`X|0bd~3q5G{M^shrebw=)3zdVrGsR7WuVH zNWJ{%r(3bX=U0A%Wu>Lk!%aw2nuAcGYCBEHVpdn|9H$N}b$TCj@WSgs6@whE@-pm@ z@9QpQ@`19h5(TB7ifRwJ0*tc=v$&HwWx7$&F`F*vcoCzWtbOdr(}?t|z`6k9Wo-~r z4PB*Le&yu`I5|kA`4m>-+I25CqGzBQirM@O?{FN24_$S;m7#+(?q(Cb{Jue|W7a{Y z#$#>F$@mCi$?di?BK9p`^J_Tv6e0k<21p~k&d~-uhi^GweePOPF4|<($vQ8VH`tU% z-zC!om0ToF1n+OLQaAyog~#rQaQtz)&s&SaDoxbOF7waB`~k4iF}~^@jc`V+O>U`= z?j4Tk-UX(R(lNDk@Q<;CFzE z@Ho9>?O`MB(X&?)Brl*WE-%8q+q#i<@7Y{b6JXg$l%#VHyj3_+K975$zY|bDYCg7n zLHAZgs+QrcuRpe?knuuuMtU}zg31oxDEi4f-=|a?@j2 z4y&0PBuk~)4t-J>Fbgf$H%zbPA;&z5LX!EEwfu-9VtPUz@M!kw^vYO8qOjG82eSysXZ5vR&Xj*9;|uHwduz?T~#?$(S9%*=cz*i ze_oOsAWAIEGA+4K@w(SB9SP6xOaaO({I%Xu9L-KBj4M_r2v#xf+ppz+W#7`uO!n!O zv&b=`t>lWaA@g?%j0h6=Rno)JHB$K15?K!H+b=3^E1&W`IuHdL$)xZQ#(7aZXE^}W zjP_{FUztL@q-T$L5CF?0aGJa^h4Abog>P#%1&ZqK3aPlg-i3)|)WrIdn8kv3D4DrY zO$1q312UZJ%)pPCOfu81=&?G`p>%|Zmg6$!_7~k_o!uYA#|X=l z!JD4<W1iLG}Rq@Lbqaog+C=3}ltt*9O47{eSPGEKr84=&$DkyT&v{PG&nJ{g5# zfmJ`Hno=P1$_L(l8$4v8^DB)UKS~IV51`h*7M_ETu+ls;m z$nJAR-ukYCHb&oD>3OX8sfxc!Igt$PO3Wf?#MFQx!v{}e!fCbxi4hBk=pq{^z>)sq z8I*d&aC4Kuw++Mgm6579ds(XqHl$#K8s>fg(=oYsP2k){3!Vv)wgHEVmO#=&Z)}N2wvk28aOnz*D5QZdH2(Whth&2?qMx9pbB;S-0GpV4 z18BuIW9WWK=)i?*7`9*=U7Av7fbP;iJzX`}@$hgUG!G4KfTa96@Bs7zr|3qV6p-IT zB?)w|DP;vHx>Lgn0am*Nl{bX}m;qXXVT>dqJ+1<@DUX!i6Uhp;cr(LdejI$u_5t{o z?|xJmrFtSgSR7TCq&xtvUL}apDH4FkX5y7l%JZxb2i=PPhId{hj(Zz?={9)5KfhF0 zXUdxtn)GVl5Qo=aG?fCpge<8EXA;Qd83;4)U~gpou^|W%&PJp|{>Kq0cK_G!WUO?Y z{?G{O&+T6*d5D&23CjCI0 zY#IPQ_#s$5zW0ag*d*C90IQri6?!aMNP49J>kvsfrEp(O2jGlM0JVrBxzYh1)JSWW z`U2pSlr*oNTmuRDK|NwWoz}jQ)IrO@(yt`*F2>+q=zZPQxc$mZgT>3BpD}aO`p#cG;{sLG$ko5F!0&swwh5TZ` zp8V@~%#Vssf2h1@)0YM)#2h$~d=hxyhpFeh0Ga0br*t;UK;|_QMCR$Vc7MLho&SS4 z{Spii)BL5TU@Nb)B>@fe^-t|T4|s;C^g6e$1Z$~hNAnm-4?fnF(3A;qREx7yWCAtVyWx*eK_kWWP z?>CUwB06k*K^sr(OtgLnl5tU!K#(6g0cL3RxN-&*qzRa5z&ChU*JfQ>zi{PNGG z7rY?bXgO7zM&!SU1PT0KUbo;yWI6Y#r31j%KV=UTYW_t(lc3p4iuWO7L;sfr_z&s$ zWyH^(W{B=g;T8K^LzNS4-ng`L=k5dDf4W>ep9W^Dj=zZF(yf#}qNRQQG3>MjJ_oe7 zfcW}HM1cHNY7Cf|mjRf)(BjA^C%q{Ina8Crizs3dXZ=E5hs5MA)>5D?^zUKEw*nGj_$kFu-=X(g!CKq4%=GJ@ZrjTVL*-hye*6f4Yq3|63HHr^dXqKT z^*G~)0KH8xaCjb---K-WCd_tW{!6434f-yKgFvcz3eEYIDuIAXOeYbxD;B#=h!pEn~)}rjE%Hw*0Ae5pg7z@XDJufE{opK+{PCJddOu? z3h&#PURnkQ%;-O!AgVOg{RgjbT}AcIWrbvR1(9-jYyC>5eW$@fLFrPvte-@J=T&*{ z-qa(}vHzN!_nIT_#p8-qL8tw(ERhm;=BxQ^R7+c@MbTg`CWjT%sJg0xycTrdY1}bg z=a#FP!B11-d(tM{AC-0&$`mYTyDtXMwE;%D;EdXW{&m(SmQslgMKr&)^8?EwblOTs zRS|L4^|vb>IWLT#S!!)$5xxcW2bLTb057~Sid%-_66%h6r-x{EA)G5`ux#)s=rL@c z=YI1wI9|2><`1?<2RFCI<3}0QDy(tKiVnZWxB#x>+s+zStva1!ZG46(?n5=Y?CfrE z$Dsr83FV-e_@|zSu^}B@P4z}oV}YtnBT{RggVe%$be8fnd+BkK()87G4~cU{cl9PH zI@o7O4|BSdA8N5(aft%lM&O3&&Uu?OAr-e>_CLd;N`x)ea($!PkraU}ulA#eXw`wZ z?*Jp$3q#7CUUiM z74=Db0?{2Z?Unj^z)F%j+b*aV(^eV7DyF&(l z`&NU^b6}dHi>5s<`9|J#!_#0{f<&4F6Rot3KMj_}C6)txBq9$GukS;8M0~18EtZex!AqXwrq|NQ#0oxA4EZ)>CdG6~zSAr{zprO5R9qBwg0B(lVyoM_z^2zIY zn!m1qO<=^}5uXYejgWd(xFY4HUC~hNiLSD0clI3jYC!oXr+SpE=Q>%b+<5c=m;#D* z%PNYEmhu1tVw~^H;c@%vjU)qy4vVuT_wjG`Iu<^+OB1!P56o%{@9h5&D3b7Z&YR*%~Osxx8~ zQ3v7T=;8S_;s|XU9kw;VPY*lTgmpa77kcPQyJI|@qrErTQ?_?3Iqq^)FgYQDanGuC z)0aQ=ugP?)K%5uB9HMY%3o0sbPDFOI8xB6P_?!9hytq4j+vH0 z;+}EBQD0p%JFOBgjrysLoxe0oA>0s?0Ip!@dAz(gPdJ6JrV6W!ii;VstHFPgTX69lL{I0tK}I1qH#*vt|r zp)QJ8WT1D)_0>$S`trV3866t3QNY*w*gvwsx?OZB3uN;vrOHkMyB5c<@1_nP0&DWE zHM)TdgoLE?L=)*zk}}%b+F~u*T3Sp%`I?N$y+MBVPG;&{=@^q_^EoOqx)UBB&212{ zNl1BZ(N7Y43pLTg*?!=k7V|zzrY5u_pVM|QVAEqh#*Phv$UE8(7-92=q3I;8$)e*^ z-5#845$T7Xcbs7Neqo(-B+TKy`{b+hRd_!84K+|vr|t=GgR$q&m(Wepc~>_g!A%^& z_{8|GfRxf%{(fTI*VCUBh{vi@)2gN6B@iqpsp}fYW<=_q80iLEdh+ zCSP;cOW3XcFa11^dIGj-yNFTWHhL^{YrRzr$ z9F7Y4h&^bNT%GiqZcAQ$cxU-CngZiYY@B?3Ed}&ji6hpQ6XFUl`rgX+ z8?PGpdTqC3=gp7bNJwuFC}T@}27|AM?a1-`QY#G6%RB9yDBQ z()u#BS>HI_u~L)*?XZBGb}t19BSj^y4O zQ;ugCorb*5;NeFphrm8iEd?}_QGk2NC?frqop{J`R~&}pGnps?S-TjH_`Ed`qZ$E# z8*~VCU}lvaoLGp;cf#^$J4}@DZs(|(`|)NDf6@V$zFszD#Wf-U7YQliQi~v=8VjU3 z%o!v@4p-ZujKa{DF{T;nXNPQ-)x)DGk3ozlLM*Ey2B9o9TOauB-Ej}QhojG&3MTNfneUY==&oHD1ktpq^w$ue!BF!PMY)NdE9i_c*vR1hcI*xRgm{~0^7Se*1 zUAy-eD}xagzw=CcJ*L27M8VJ{j71Uay*dc&FPeh|jSKIUh3*cA(UDz3m zDTA?%m05KMaWq4yO4arCp4v{t260}$VKv)<_+qh;z#;z;$Rp9zP?*5ba`5zNZEeth zMEti3j|rn+kGFZzRZf@mt`bM3>ZJ{@FdqEo*iC*k8I)(l=fBt%&Q~t0fzRbudT%Lv zGG4N~>;#omdCB-(nps`-P-_O}4gut11bywO3=~ot<+`LqSr9Ui;1;){Ki2$91y?Vf zX~Ozj>s?Bax$s11-0(46%iZJdqbu6i0{B?rGm&&RKv2UFpt)NKRmDHh`biuv*u@Nn zSa!MUvzAoO-OxP)wGM27((d0TAq^#+$x}JmliV9mk3MEGaeR%(P z_Rvi^Tkjub7lcZKlwCY$1_-Ck5@(mgj<05R{J)i%sn-uq43`!_)&|t# zE09%uZ)3qgF_4`UnKdd!k@Ig_M5#_of9CI z6@}zuIj!H_2t{H}pypN&!Lh5|tK$?5uxPCirhFUyS4dcL&1VTW@$Qh|+GJX#<3!k# zdmpj7mY?uO`^N7!O1~7G)`tM)idZrafYJ2%e7u^|q3+3qKv@OqTTn!yCCSEOsfkSfd+N&z7X>~Aj=>Id zE;5RB89~G}StOADq#phT^?(@_w75gyjNnP04)3Vg9x9a8X+0O06rPzh^FO>wyq`H2{AKuwYJ}H{je`^C$lAlrp=Yl(J+M5C5O_)QkFfAr@ny2(u?klGB`3euhx9y#{w5KTn(7NcUX> zpf`@i#T(L`iC~HSiZ}Mqp)?U>49}4umc@`YcRi-&Tm17mk5!sEUI&ossWKb{tu-uW z75YDI-9(1$unB-?Xk$1a3K}tIkcf^cob(*Mf9F7@zR0mq%tN33JTE6^_`r9&?cDwT z7Qk{0k*($VzlG%l?bsfM0k}MA7B)CswVkT=LnS%&>HCzB^1A=r%mGTom(hR*-a4MJ zL4WxdToIe>>II%xc^2TBck)Dy0%C)%T@0fZT(go=pVl&4d3>a5DP;PCQR72ycA3*r zbDejYgg^bDZ6HBE=MCEbhV40|FY-i2t`EZcuXxjwF^`t+=!dLNU~-;e<*p9DZ>6E^ z=k%5@6;rI%s@_Bok&m?dSeMyO1@wAmg@xfnn}aY@fV9!|rpQO)0n9G&Pw61XRUd}U zT@e4$H8W7j)trHUCtcR8YtP|CG>u6ybBkz@%u8udQK z=zQU!E}i}@v?}`F%9n7pn5!Ps1ug}U-m;F?Tg{Bs8M?%%oYg6qO|;bIPeL*`R_rAv z)TZXD8Uwki;zaRlP5Hn=Q9bfFY z0NZH@823SjT}OhjgGAn5swHeCZl71aFuT>?^*BHMlw^WLA!V7e}+3-gf7$FJ=mV!||ALwkDBbQ-j;-eB|A5Q3g6sRTkNk z76GgDA3%pJY5Z6gz7EG9t+f)Ll;W^y87ryJHBN50;aXN=-s@D>Z}xD0!0a_`{UqMr zD@>43wZAP5t|2;Uo>X3$cJe@#f<_3HNIM1?;FiFo7BW>@ZdLs@rT^yxz`q4@3U9xp z$-R8&qh!6RXTYEo#I4Wxt*K3`J{?`bq=(=2WYF`yLtW(7wVdW~a;3AF{e4=m-I#`M z!QMl!m4HkBDjpRwu{m(N{~G`@OP=yAqmMV^Ul2w+5pr}0+gw`BcX5R^7&rPbnX~O6 zkUK|awI+DSX3FJb{2ky^mJ2oUPYvBts1&u1Ja>&Zaw$V^9?HP#K`png*e-`r^T&Z> zcJTKj@Yv#Sn8P5Jr3YqRqE|k@{36koac!^MXMI6}ZtxR(eZPg9hSxCYkBKkij!R`t zIJ6Gk=pX3bZH$^y(Vxzg^nL63!NC1^{S(g)=PqFIR)5YH9(l#PM6@OI!I+)Jh17)v z{K{^P+?b%54;B+XbK5?v&uR*xZaz$c_?jH}3nrlquHb8=@j|&}L_Xpbyz&;S>s@OuUdn>=Z48Fwp>!)(oah zKU148U_gL9#9ya`1vNzcwB17+FuDibN3J}VJEve_kSad|Pd8C`Ntw^~x@z;$v0b5w5jneR>iNEuWs zJQly>h|}&ae{9iZvDk&?9FM)gVkhALvAgQTxbY+Txy6AD%f=6W*U_?j@7)10mfvI$ zjzRwt+WywR?vQVT+YE3Jp-S~L2Qz74B=eM$yx>4AF)pb6?Ca?@E^rZBpZw8V;kL&T z*W*+D2g)gub)|DSXKAtED*5!|)>r_3;-JSGZ4!5O#++*Kiv1+GLy@ zh)Z&qdYzSV+xrO9OS>2(mEta*v>oL$XKNNi(mrQ5EZV1~ptwtr3@kyN&ZZ0M5M5vi zkzRYBpCRo~2dxET-u_~E&j-MKE@|Fvxy=U^Il|Dx3C z>rLAk@NT$#>>rQci(71v49gR-{0l;wFHv3Ig~QX}wTcU{o6^t&6aFpDzK# zHGYcOOjJC>j0X^r3P^a??)zE^G)n~91j4CvCm`}U^WiKzOQ$U89i)HF8mcGZEEiMZ z#H%gVUY;5JT7M*2xw&ob?PZ#(5R3}M08zAv_p}R%<84pv*@mK`gHAk6kvg@{BTf_F zpr9HWhJJZjMd>p7OA~dEU)8>PBgt7>KUkMks1JyvweEfW;rYTbkJ>2KfscdCpJOZ7W}}E7vI}Q=$L6 zN=9$;QVE^nPP1=07;T*&l-77)6jQZVAl?DS6VCfk;|IWqg1P`tdslIzNPw=*GH_b= zpIZ(q&Z?MNN;lNxj(nx%a+|JI{%L)%F|fUY1v_lFtdrO*cW!apAhG@CXXh_+SDcby zOAf&Fcs#OtOFrV%(Q2u$fc~ZE z{4jy+bN6$r$%6R!S%SRuub{tp^Y5ZWPslHh^ex_P);^;%D`5Xw%TS8pIA@T!*V&{8 z!cKRSwQJ7u0dJ{58=qAtlz1rCK*lKS8+}c(#5a5;6XLh(1<$N=WdPWBd&_0?Z4#Dw zu2WH%9_o>;CqD^ZAsvV_crdY&wkttW<1tA17EY!=8TDif<4~C!`EVymq?3-(o`!ta zgNX_OnowY)dKKdIX@rxi;G(sAN`=y!>cQFOc5hlh z`iQh=Zl_r1-SpLEU{R|cni3fAI+3{ZXfm&^7>BOyj6A+zxb}H$Fl2S*@wPYkSa$=3 zh&Sq78w25Vp3pg0Q(&Z9o8*(DMCs~Bxx1B^IuhCavuA{9d_K2CAI+-}MtH*w8Ru_V z>yG}TX7OcI!T<9mdaW4P0%dJxjy+R-$iB<-=m}ji4wHObfIg6#xl! za(5FDCwAtFdaLkQ#IWr$+N1oXU|v?JCnMj^GjRvVgg@_hBdR=0u zUlpzqs_eGwWa}r&ldnsR?~m#?#wWZ-Fn@$?;j02K6VrBP{uT0oY&6k6i{+m zNhxEp3re{(gCBZ}lyMg(RxB;kbqp`C8yPD2Mw{zdB}{(filqhA(6kW?pC>b)+2&>AIFVua`rEcmfU*zAZ)m3M4$D* zT?a3N>x*@!s}Oun30ybw0^V3na<)@eyYHXD<4S-v)tsYPZpNO?s)_a z$IPo7a}L2dfWKNy{@=`8OQU|lb_Oos>rOYk`;P7D@WyvGHP8un5{6pqjy#s5ra;PX&L zyFN>K(>}d4M$8y2SLG|CX6o|?qNmvxS@S?g`qHm`ds}msn@`Zt0L#Ci-U-!&pOURE zB_Sj&MNo0w9jB#;&hY~6^ia;i^U;!b^{}z4LtR=T8}G0(`{CulTcCMfLzuYz8l!_> zY0U@Ua1V93K7k4!B#^}*$?48|JQ2clZzR@NV3;CAxzd0-!^wBkyC=$bS1l|aV_gt? zE*w9(G2UNoWWBRhPvnEJ0P*2!B2ssGt}7wmw7((Zb`fZYD2g5a z!~JTW5@X6t9{N7+O5gdT4M$Sa19e-s*)9v)_CDxJU+1nQVgBq%*mAV4?ObY#?$?rK ze4Wv2*y-$@P=0nGgwDVHkaN{l4mY*bH2im}(%7-9m9IfO`4+DH2pf-gqu7Bf-!Q0l}2AkDaUIHHDUBJ4A;NR?nZ3L-{YTWQ_{ z>l2INK$2J~xZ4PST%u3Q8ld@b*j+C1ixZFApc-$0N%!mkmMEY!BiHuUDv;jbfig`X zsfF+f`(&VyfV14~*;#24dFsF%puAgvwRj63HZK3WgZz_kyEd3Z}}BSh(G! zX|Z{-`W2ou)5N^g$=CaRnH*5`Vz|QqqXfM9Zn8h`eq7Wb&4F6!8`7}st)dX=(1>5MP$(#WKTxmo$ZGZ|optQyKdqJ_JKV%j$La3)ago85XI@dcSw_G0zN0sKO_e>~$ zIKXtDrS$LHNOuGCI>Z@y;FJ(-zZzQtjc6_c{4z4|u+tlh&Pq1QL;FiJ^OW>&T0ux$twS)9$M{i!qXn~SzVE#a8T zSm!m=aBd4chE+rK71LWILM{MD8@#3&HaL6MH{3w542ox>i#mWglO-f~O)kz0*mA02 z>U+9X>Cb7p^)}d$3wB^U1aClUm7I#84jG(G$R>t#!59=mx*~>AZO$JVKiJj*P+9k~ z^fW*SwNX%e;V0cEDql?l!=#WRrEIgzLl%bQO|N|$lUmQ40%9pS^=~^aByBg-86iK8 zRM1+GW3(yy{!@@*{lVzpyhi@P!J_p8!Uy5bb&{dF%!b$kXNwbj=L|tV2N4C76ZVom z8BlpWr$0?3*x}PzNlu03ulr8nXZ-UzTyNtdNU0+w35dFy5T4KaK&3E2Ume#|fM7m= zM2D0cVk*4|hFP*d7{Q;CL8ueURbNUA^k z*HbVn2pI_?6qZ=j5#(gq8|V6irhj_~40(vK_7EuxSiL!oYeQt;c{6@3Y(O_qXnF|@ z9c9-uyT`8mREHeWG5wux^W8+C*W^1vYa(DvHSq5NmJA#U@zh%2d7r|mwLfJAPxT|fBJ{M z&~HVJ|CBS`^S>q|1+m!wfXNJ(tuVcJ85OtR9tkT7{J)*A&TG-~6WDq`eppgcVwWBB zuH<3kXSda?qS*ZaNKk==CQF_^mmkzij1P7TU9x4(LFw&_h z9@gVPaUi5nL>1us{%sQgDYm1SemZ0~-w7(L<^lVxF)3^?GB{f6asIjYrQefLzngX!M;lW0ckh&92HJe`9y}(1!Lfveogzq7QEaAR_Goru5{MNxTzmk}L zTaj#$(YWNMW7&m3HvDt?a$}bRNZKG6 z!Bt2M$6pM=m=vE1z*8Q`W)^0MLS*HvwpbAXamE6YS?&2tW>tc4>x?wJoL#s;UN+@X zAqpr>2tDh1rM4B+2qlh0UuA-H@t<-Fl{AoRi&yO&B=N8`ki}V1_G!K6;g}Fx*B+Dc zU-t+QE#F_eH8zOIrlnwyAjb_wQx6)&kdxqqe(JTfkw!Ln)^y$OoL@RDzYf^-QTg6? z2317);n|Q4GE_gHuN%XHj1XLj06GpS^&H4xIU=}#EqcXZXTs1fH!FaPOb21yT%g>Z zrh%JqL4+Zh0Z~)_4_o?yJ4+x4^hlygepDM{&>o!55WIJ?jN!EXFmMNef3;Ihc^gaV zEn3xLTOeS*V>loq25A{_QP4awBb|&I*WeqQ4lFMe;jk>)I+bybHgcYMb2$`|H~W=G zt(HeU95Q5KpgzKrCrf(wIY@U5UYy(~kp!vNWQw-?li z#NQJ}p&o#@-;D;Rdg}e|D}(nAD}P2Eo%^^n{&kdYvF*qQgM=A6*1A4LqSl(Uo5gt&L;Q}} z)h~ci_eq31eL{#gzzoqpIYTID`{8Kk4EYhxi007h{Odx~{kQx?KOP(#EzHc>|5`|G zM(h0T&*h4>1qWH7mS|CKNa??iPIad4tazYDTcSbjLg^Q$go7~#xys#CPvYEDr^WDz z-knC#iUjJ?lTuByld>+?rDL=Th+01%ZiVf%VM|SNv&Txq^D5C%Gf%077oy!y_?fWL z6kU`-$&w#EWe#5WSTPsH%z^hPklc~Mtd0qlQ@=`vRwGW~TV!VReKr%@aj$v69E3$U zw*_FyX!37hI?)j^a`)l~Bh9ZU*w;u*nf<^d4VNl3gSa4rtvAPRe%PymAjM#Uj|E^*(AgGpG8Z7-jP z5);GGl=p0J&M)`LRlJ9O5h_Y^l^cIB z+6a-kCl}|2e1X;4!S?-6&iS#8I!^hpdklJA8k-l(V;hipx!R$!n~%EiiouV zt2!^i+vnKHex2xnuj)l8ZQi11tmseD!oJ&SMTY0Q=NNQQQMDNwUS3{LYNb7VG@hLE z9m+1kZc+2$OPrGQL9+Eb?e$jQ4BdD{aA`8;XwP-q z_-taXOPnEvAvn&EfS~&{`B+RVI%3BopQ$K|!`i#|_?H)Qk@8D&t5LPvLBC&)DXK@4 z%mQvVkwkA*qLL(<9P_Btp2l~3k(H9HKOaiFqFC$_XWhQ5IL)$ zO^%vS^ngEUU*u{A%Uh()#1=9@wrCwVHy!D9VcNY6zqg)j=3uKU}4>w-I>g*V~)vDo+?G%AndZO)MGh;-4Y%;X%&%*g&MIRoaeD(4$bXJpbn#;qR z)-PJTjTZYRmlWOb-Z6;7Um2xcy6sschn5{s62HGioM@rH<7XAAT%uTqiU;q`I;W|5 zjijLuM1`&zls>)&)7ZvlklQNoN|iu<;kC8x7+`(v6ar7vTnxkHpd+3ai*ZCJl4tC% zjW%e%boXI!&0z1Ripc9E?{b;mt}^;+ZkN!@y-}3^FwxshR+M@v*}bp}(u?(hS-o&( z`ANQ^!yZR}y9eUkyMdMJn!ku>4d|EbjuK;=oPWt#8%J}Qn?`^jXo}&ftpdUq9_#JAtyT1-mgK}3ZlN%gL1BUdAK~Y$06v5G0I!B*RL70htzv*dEhk3 z%Q+%EQB}qGscyO6%{gD1`mxLC&I?r)W2a4gXb4IiAW7q9UPFeNu=g>OTj_iOa5rN*y$&krZvesHlNDL?w-{R^O_5Xs7@N!)%J?A^Bg?IRBubPveSdQ@P4&0R{ z@#qz^mX0C`?}sYT4V_fRw=nd#!;+N;7JQBqWf7-bG`p0XP0IWbxGmp7sr0>(=8=KM zDRu+;{*zMDT(9Qy*LZhGmTTVuO>`|B?&Auxv$`@?Hk0#WP4YQ=(zj<)t+Ex-S2|A& z?#S>tbZbioF^ZD(tDB;q$LZ&sA`j%s=5J5qx41ofX$eubs0#H5?o(ofs|UeF6*X2i zEn_=Waz5|2F_Wj$w5@f6o3+_cv6ErmQLL=ZRr0Bfy{XC~Ss^kZqi!QTN00X$NH#); z6HG6^Awqt*LwHIjG|Kx|o`?zg_$z_^`L+Xb&!0MVef!ci`siI{AxQ5r=Fwo;z^7dt z@aGV$;XI`I==h6@w;DMsGsY7{@mvIH{f%$K$@I3Nm&YH4Wc!T_;(|yq;jAZ~fGktz zt5YmQiG0_G|LHy`l#?M2|o`gz&2(r%B&Z|DZ| z66}w>F0!BOjc1Zq>bq(?`#d5E`*XR>Jjh{H8O^iNznPyV7H4qp8+8l z`qR%;Nez#})|o>USyT%Ug5YM4=Ppjvg!PNs?_6L4L@O_&8%jsW(WID$(!vwT*xboL zf_p7*IuQYz;H}TOdWm2nU3rc)v#Oa&G4H!Tp_$-Cis`vj8OS?uc*X%C^Tz8f942VB zZd5;nQVZfF;yRSuo(t~I0ST6^grj7Wbp^BBj;)w!TtmLcY3HJ{5P|`v1rg0Cl99g9 zh19w{qfaD+s*z$3w$s}jhZmh~YVTy+X#CWE#EPV4o42c&O6`yyqSU$tjW=gtdI>zD zRo8eu*UasQ3JN#~r!kSbt@_}Ag|a*0E-sF(L=shX zlr3u(ekmrN4%)IRCv+lbR^8^<(8^+tTfpp^`vCV-4{w~tskfaWX%p47j0Dz{(uaLz z?Huhfm3v(a@dMYN2ruWENSj5Bti0%IHt$Cy#ptTf2ob5Pf=OzyIByY+G1$uGq<9jA zezGX=^j6X|ldn9lJmK(@qP&}*<*SuFg@8bR#x8%s z7;p0Mf3Q;F@SLY`nj1&iZcI}@g|Y4~Uakz9k4_RtZe#qIFNudy}jd552Wl)?>&o$Wkl2$AnQ zgWL&2;iieyr=i2^krMU-(#Gz)3*d^nD?l3;Haox|oqv`~k5|A<2&E7FUv(2E#$4cCpECD%U&a}z#H_w#VS3{(sD zLzlCusB3>SMOOF*kTaw}EJYdKR;a}0xA`OC?i^vi=})*^fgFW*7?KW7_B3S|DYcbJOxs>-HrUc3rZ@pH+-RQ&6Tf_8ry zd?sFvFj8alK*H^?@aYJX99gp|(|=e}030(Xd~O0MeOdUL|6*5wf|d1*jNjNPop{lc z_W&sRZ0&)aee3L}%3?F?PPvmk*?|}%QawL`5nmNcpOd^jkD4F2oNS-lzm%KhX3F~! z#C?(OFQ}!gtd!gv3MqNxnyV3izRK>xM5*$M?2>r5%cHgAGkB@DqoYam)*1Il+ivTQ z#pfn}dOV5Wv(w1z!k5IVLtL&+Ayz9>GsQ0+6w+wV7oA;cU2wKFAgB5+oU>^JzyEhr z&3x0~Z~XTc2J4@{t2T!nlY@l$-9LY^z8m#XOZ`~3n^rIZkt~p=`W-GhAY1Zpzd+ss kaIY - -
    ROS2 Machine(s)
    ROS2 Machine(s)
    Sunrise Controller
    Sunrise Controller
    «subsystem»
    ROS2 Interface
    «subsystem»...
    Robot Command
    Robot Command
    Robot State
    Robot State
    «actor»
    Motion
    Controller
    «actor»...
    «actor»
    Robot
    «actor»...
    «actor»
    Visualization
    «actor»...
    «actor»
    I/O
    Manager
    «actor»...
    «actor»
    Motion Control
    Manager
    «actor»...
    «actor»
    Robot Manager
    «actor»...
    Handle Error
    Handle Error
    Configure
    Configure
    Manage Lifecycle
    Manage Lifecycle
    «actor»
    I/O
    Controller
    «actor»...
    «actor»
    System Manager
    «actor»...
    <<extends>>
    <<extends>>
    «actor»
    Robot State
    Listener
    «actor»...
    0..*
    0..*
    1
    1
    0..1
    0..1
    TCP/UDP
    TCP/UDP
    Condition:
     {Error could not be handled internally}
    Condition:...
    «actor»
    Configuration
    Manager
    «actor»...
    Viewer does not support full SVG 1.1
    \ No newline at end of file From db6fe0b5b5205922c95a9118354edc3f6d333416 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 15:38:02 +0100 Subject: [PATCH 93/94] change getstate name --- kuka_driver_interfaces/CMakeLists.txt | 2 +- kuka_driver_interfaces/srv/GetInt.srv | 3 +++ kuka_driver_interfaces/srv/GetState.srv | 3 --- 3 files changed, 4 insertions(+), 4 deletions(-) create mode 100644 kuka_driver_interfaces/srv/GetInt.srv delete mode 100644 kuka_driver_interfaces/srv/GetState.srv diff --git a/kuka_driver_interfaces/CMakeLists.txt b/kuka_driver_interfaces/CMakeLists.txt index 5aeb3a34..7884231c 100644 --- a/kuka_driver_interfaces/CMakeLists.txt +++ b/kuka_driver_interfaces/CMakeLists.txt @@ -22,7 +22,7 @@ find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "srv/SetInt.srv" - "srv/GetState.srv" + "srv/GetInt.srv" "srv/SetDouble.srv" "msg/RobotState.msg" ) diff --git a/kuka_driver_interfaces/srv/GetInt.srv b/kuka_driver_interfaces/srv/GetInt.srv new file mode 100644 index 00000000..e360ca99 --- /dev/null +++ b/kuka_driver_interfaces/srv/GetInt.srv @@ -0,0 +1,3 @@ +# Get an integer value from the server +--- +int64 data diff --git a/kuka_driver_interfaces/srv/GetState.srv b/kuka_driver_interfaces/srv/GetState.srv deleted file mode 100644 index b2ea0435..00000000 --- a/kuka_driver_interfaces/srv/GetState.srv +++ /dev/null @@ -1,3 +0,0 @@ -# Get the state of the driver ---- -int64 data From f94fbed4dc453ea67dd7f859c27d61327d1b5581 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Fri, 27 Jan 2023 15:38:14 +0100 Subject: [PATCH 94/94] remove deprecated tests --- kuka_sunrise_driver/CMakeLists.txt | 33 +--- .../test/lifecycle_client_test.cpp | 155 ------------------ .../test/position_controller.cpp | 110 ------------- .../test/torque_controller.cpp | 102 ------------ 4 files changed, 3 insertions(+), 397 deletions(-) delete mode 100644 kuka_sunrise_driver/test/lifecycle_client_test.cpp delete mode 100644 kuka_sunrise_driver/test/position_controller.cpp delete mode 100644 kuka_sunrise_driver/test/torque_controller.cpp diff --git a/kuka_sunrise_driver/CMakeLists.txt b/kuka_sunrise_driver/CMakeLists.txt index e63f0a1d..0e5cd5d4 100644 --- a/kuka_sunrise_driver/CMakeLists.txt +++ b/kuka_sunrise_driver/CMakeLists.txt @@ -59,7 +59,6 @@ add_library(configuration_manager SHARED ament_target_dependencies(configuration_manager kuka_driver_interfaces rclcpp rclcpp_lifecycle std_msgs std_srvs kroshu_ros2_core controller_manager_msgs) - add_executable(robot_manager_node src/kuka_sunrise/robot_manager_node.cpp) ament_target_dependencies(robot_manager_node kuka_driver_interfaces rclcpp rclcpp_lifecycle kroshu_ros2_core controller_manager_msgs) @@ -71,22 +70,9 @@ add_executable(sunrise_control_node src/kuka_sunrise/sunrise_control_node.cpp) ament_target_dependencies(sunrise_control_node kuka_driver_interfaces rclcpp rclcpp_lifecycle controller_manager) -add_executable(position_controller_node - test/position_controller.cpp) -ament_target_dependencies(position_controller_node rclcpp sensor_msgs) - -add_executable(torque_controller_node - test/torque_controller.cpp) -ament_target_dependencies(torque_controller_node rclcpp sensor_msgs) - -add_executable(lifecycle_client_node - test/lifecycle_client_test.cpp) -ament_target_dependencies(lifecycle_client_node rclcpp rclcpp_lifecycle std_msgs) - pluginlib_export_plugin_description_file(hardware_interface hardware_interface.xml) -install(TARGETS robot_manager kuka_fri_hw_interface robot_manager_node position_controller_node torque_controller_node - lifecycle_client_node sunrise_control_node +install(TARGETS robot_manager kuka_fri_hw_interface robot_manager_node sunrise_control_node DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch config @@ -113,26 +99,13 @@ if(BUILD_TESTING) find_package(ament_cmake_uncrustify REQUIRED) find_package(ament_cmake_xmllint REQUIRED) - # install custom copyright name - install(CODE - "execute_process( - COMMAND - \"${PYTHON_EXECUTABLE}\" \"${PROJECT_SOURCE_DIR}/setup.py\" - \"egg_info\" \"--egg-base\" \"${PROJECT_BINARY_DIR}\" - \"build\" \"--build-base\" \"${PROJECT_BINARY_DIR}/build\" - \"install\" \"--prefix\" \"${CMAKE_INSTALL_PREFIX}\" - \"--record\" \"${PROJECT_BINARY_DIR}/install_copyright.log\" - \"--single-version-externally-managed\" - WORKING_DIRECTORY \"${PROJECT_SOURCE_DIR}\")" - ) - - ament_copyright(--exclude include/fri_client/*) + ament_copyright() ament_cppcheck(--language=c++) ament_pep257() ament_flake8() ament_cpplint() ament_lint_cmake() - ament_uncrustify(--exclude include/fri_client/*) + ament_uncrustify() ament_xmllint() endif() diff --git a/kuka_sunrise_driver/test/lifecycle_client_test.cpp b/kuka_sunrise_driver/test/lifecycle_client_test.cpp deleted file mode 100644 index 64aeca0e..00000000 --- a/kuka_sunrise_driver/test/lifecycle_client_test.cpp +++ /dev/null @@ -1,155 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp/executor.hpp" -#include "rclcpp/executors/multi_threaded_executor.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "lifecycle_msgs/srv/change_state.hpp" -#include "lifecycle_msgs/srv/get_state.hpp" -#include "std_msgs/msg/bool.hpp" -#include "rclcpp/message_memory_strategy.hpp" - -using rclcpp::message_memory_strategy::MessageMemoryStrategy; - -template -std::future_status wait_for_result(FutureT & future, WaitTimeT time_to_wait) -{ - auto end = std::chrono::steady_clock::now() + time_to_wait; - std::chrono::milliseconds wait_period(100); - std::future_status status = std::future_status::timeout; - do { - auto now = std::chrono::steady_clock::now(); - auto time_left = end - now; - if (time_left <= std::chrono::seconds(0)) { - break; - } - status = future.wait_for((time_left < wait_period) ? time_left : wait_period); - } while (rclcpp::ok() && status != std::future_status::ready); - return status; -} - -class LifecycleClientTester : public rclcpp::Node -{ -public: - LifecycleClientTester() - : Node("LifecycleClientTest") - { - auto qos = rclcpp::QoS(rclcpp::KeepAll()); - qos.reliable(); - service_cbg_ = this->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive); - topic_cbg_ = this->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive); - auto sub_opt = rclcpp::SubscriptionOptions(); - sub_opt.callback_group = topic_cbg_; - client_ = this->create_client( - "/lc_talker/change_state", - qos.get_rmw_qos_profile(), - service_cbg_); - getter_client_ = this->create_client("/lc_talker/get_state"); - trigger_ = this->create_subscription( - "change_state", qos, [this](std_msgs::msg::Bool::SharedPtr) { - auto result = this->configure(); - RCLCPP_INFO(get_logger(), "%u", result); - } /*, sub_opt*/); - } - - virtual rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn configure() - { - auto request = std::make_shared(); - request->transition.id = lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE; - - if (!client_->wait_for_service(std::chrono::milliseconds(2000))) { - RCLCPP_ERROR(get_logger(), "Wait for service failed"); - return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE; - } - auto future_result = - client_->async_send_request( - request, - [this](std::shared_future) - {RCLCPP_INFO(get_logger(), "callback called");}); - auto future_status2 = wait_for_result(future_result, std::chrono::milliseconds(10000)); - if (future_status2 != std::future_status::ready) { - RCLCPP_ERROR(get_logger(), "Future status not ready"); - return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE; - } - if (future_result.get()->success) { - return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; - } else { - RCLCPP_ERROR(get_logger(), "Future result not success"); - return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE; - } - } - - unsigned int get_state(std::chrono::seconds time_out) - { - auto request = std::make_shared(); - - if (!getter_client_->wait_for_service(time_out)) { - RCLCPP_ERROR( - get_logger(), "Service %s is not available.", - getter_client_->get_service_name()); - return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN; - } - - // We send the service request for asking the current - // state of the lc_talker node. - auto future_result = getter_client_->async_send_request(request); - - // Let's wait until we have the answer from the node. - // If the request times out, we return an unknown state. - auto future_status = wait_for_result(future_result, time_out); - - if (future_status != std::future_status::ready) { - RCLCPP_ERROR(get_logger(), "Server time out while getting current state"); - return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN; - } - - // We have an succesful answer. So let's print the current state. - if (future_result.get()) { - RCLCPP_INFO( - get_logger(), "current state %s.", - future_result.get()->current_state.label.c_str()); - return future_result.get()->current_state.id; - } else { - RCLCPP_ERROR(get_logger(), "Failed to get current state"); - return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN; - } - } - -private: - rclcpp::CallbackGroup::SharedPtr topic_cbg_; - rclcpp::CallbackGroup::SharedPtr service_cbg_; - rclcpp::Client::SharedPtr client_; - rclcpp::Client::SharedPtr getter_client_; - rclcpp::Subscription::SharedPtr trigger_; -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - rclcpp::executors::MultiThreadedExecutor executor( - rclcpp::ExecutorOptions(), 2); - auto node = std::make_shared(); - executor.add_node(node->get_node_base_interface()); - executor.spin(); - // rclcpp::spin_until_future_complete(node->get_node_base_interface()); - // rclcpp::spin(node->get_node_base_interface()); - rclcpp::shutdown(); - return 0; -} diff --git a/kuka_sunrise_driver/test/position_controller.cpp b/kuka_sunrise_driver/test/position_controller.cpp deleted file mode 100644 index c7fcdab5..00000000 --- a/kuka_sunrise_driver/test/position_controller.cpp +++ /dev/null @@ -1,110 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp/exceptions.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "rclcpp/message_memory_strategy.hpp" - -using rclcpp::message_memory_strategy::MessageMemoryStrategy; - -class PositionController : public rclcpp::Node -{ -private: - sensor_msgs::msg::JointState command_; - rclcpp::Subscription::SharedPtr joint_state_subscription_; - rclcpp::Publisher::SharedPtr joint_command_publisher_; - rclcpp::Clock ros_clock_; - int joint_mask_; - int receive_multiplier_; - int receive_counter_; - double offset_, ampl_rad_, phi_, freq_hz_, filter_coeff_, step_width_; - -public: - PositionController() - : Node("position_controller", rclcpp::NodeOptions().allow_undeclared_parameters(true)), - ros_clock_(RCL_ROS_TIME), joint_mask_(0x8), receive_multiplier_(0), receive_counter_(0), - offset_(0), ampl_rad_(0.04), phi_(0), freq_hz_(0.25), filter_coeff_(0.99), step_width_(0) - { - step_width_ = 2 * M_PI * freq_hz_ * 0.01; - command_.position.reserve(7); - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - auto callback = [this](sensor_msgs::msg::JointState::ConstSharedPtr msg) -> void { - this->loopCallback(msg); - }; - // TODO(resizoltan) use TLSFAllocator? implement static strategy for jointstatemsg? - auto msg_strategy = std::make_shared>(); - joint_state_subscription_ = this->create_subscription( - "lbr_joint_state", qos, callback, rclcpp::SubscriptionOptions(), msg_strategy); - joint_command_publisher_ = this->create_publisher( - "lbr_joint_command", qos); - } - void loopCallback(sensor_msgs::msg::JointState::ConstSharedPtr msg) - { - // RCLCPP_INFO(get_logger(), "joint state received"); - if (receive_multiplier_ == 0) { - try { - receive_multiplier_ = this->get_parameter("receive_multiplier").as_int(); - } catch (const rclcpp::exceptions::ParameterNotDeclaredException & e) { - RCLCPP_INFO(get_logger(), "Parameter receive_multiplier not set, using default: 1"); - receive_multiplier_ = 1; - } catch (...) { - RCLCPP_INFO(get_logger(), "error"); - receive_multiplier_ = 1; - } - receive_counter_ = receive_multiplier_; - } - if (--receive_counter_ == 0) { - receive_counter_ = receive_multiplier_; - double newOffset = ampl_rad_ * std::sin(phi_); - offset_ = offset_ * filter_coeff_ + newOffset * (1.0 - filter_coeff_); - phi_ += step_width_; - if (phi_ >= 2 * M_PI) { - phi_ -= 2 * M_PI; - } - double jointPos[7]; - if (msg->position.empty()) { - // RCLCPP_WARN(get_logger(), "joint position data is empty"); - } - if (msg->position.size() != 7) { - // RCLCPP_WARN(get_logger(), "joint position count is not 7"); - } - memcpy(jointPos, msg->position.data(), 7 * sizeof(double)); - for (int i = 0; i < 7; i++) { - if (joint_mask_ & (1 << i)) { - jointPos[i] += offset_; - } - } - command_.header.frame_id = "world"; - command_.header.stamp = msg->header.stamp; - command_.position.assign(jointPos, jointPos + 7); - // RCLCPP_INFO(get_logger(), "command calculated"); - joint_command_publisher_->publish(command_); - } - } -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - rclcpp::spin(std::make_shared()->get_node_base_interface()); - rclcpp::shutdown(); - return 0; -} diff --git a/kuka_sunrise_driver/test/torque_controller.cpp b/kuka_sunrise_driver/test/torque_controller.cpp deleted file mode 100644 index 114155f0..00000000 --- a/kuka_sunrise_driver/test/torque_controller.cpp +++ /dev/null @@ -1,102 +0,0 @@ -// Copyright 2020 Zoltán Rési -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp/exceptions.hpp" -#include "sensor_msgs/msg/joint_state.hpp" -#include "rclcpp/message_memory_strategy.hpp" - -using rclcpp::message_memory_strategy::MessageMemoryStrategy; - -class PositionController : public rclcpp::Node -{ -private: - sensor_msgs::msg::JointState command_; - rclcpp::Subscription::SharedPtr joint_state_subscription_; - rclcpp::Publisher::SharedPtr joint_command_publisher_; - rclcpp::Clock ros_clock_; - int joint_mask_; - int receive_multiplier_; - int receive_counter_; - double offset_, ampl_rad_, phi_, freq_hz_, step_width_; - -public: - PositionController() - : Node("torque_controller", rclcpp::NodeOptions().allow_undeclared_parameters(true)), - ros_clock_(RCL_ROS_TIME), joint_mask_(0x8), receive_multiplier_(0), receive_counter_(0), - offset_(0), ampl_rad_(3), phi_(0), freq_hz_(0.25), step_width_(0) - { - step_width_ = 2 * M_PI * freq_hz_ * 0.01; - command_.position.reserve(7); - auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); - qos.best_effort(); - auto callback = [this](sensor_msgs::msg::JointState::ConstSharedPtr msg) -> void { - this->loopCallback(msg); - }; - // TODO(resizoltan) use TLSFAllocator? implement static strategy for jointstatemsg? - auto msg_strategy = std::make_shared>(); - joint_state_subscription_ = this->create_subscription( - "lbr_joint_state", qos, callback, rclcpp::SubscriptionOptions(), msg_strategy); - joint_command_publisher_ = this->create_publisher( - "lbr_joint_command", qos); - } - void loopCallback(sensor_msgs::msg::JointState::ConstSharedPtr msg) - { - // RCLCPP_INFO(get_logger(), "joint state received"); - if (receive_multiplier_ == 0) { - try { - receive_multiplier_ = this->get_parameter("receive_multiplier").as_int(); - } catch (const rclcpp::exceptions::ParameterNotDeclaredException & e) { - RCLCPP_INFO(get_logger(), "Parameter receive_multiplier not set, using default: 1"); - receive_multiplier_ = 1; - } catch (...) { - RCLCPP_INFO(get_logger(), "error"); - receive_multiplier_ = 1; - } - receive_counter_ = receive_multiplier_; - } - if (--receive_counter_ == 0) { - receive_counter_ = receive_multiplier_; - offset_ = ampl_rad_ * std::sin(phi_); - phi_ += step_width_; - if (phi_ >= 2 * M_PI) { - phi_ -= 2 * M_PI; - } - double jointTorque[7]; - for (int i = 0; i < 7; i++) { - if (joint_mask_ & (1 << i)) { - jointTorque[i] = offset_; - } - } - command_.header.frame_id = "world"; - command_.header.stamp = msg->header.stamp; - command_.effort.assign(jointTorque, jointTorque + 7); - // RCLCPP_INFO(get_logger(), "command calculated"); - joint_command_publisher_->publish(command_); - } - } -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - rclcpp::spin(std::make_shared()->get_node_base_interface()); - rclcpp::shutdown(); - return 0; -}