From d2dd7624276e0c582cf9c896aa390d39ea701190 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 29 Jan 2025 18:42:52 +0100 Subject: [PATCH 01/26] Use jazzy branch for realtime_tools (#2019) --- ros2_control.jazzy.repos | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros2_control.jazzy.repos b/ros2_control.jazzy.repos index c93d8f4ef6..9e5e3db80e 100644 --- a/ros2_control.jazzy.repos +++ b/ros2_control.jazzy.repos @@ -2,7 +2,7 @@ repositories: ros-controls/realtime_tools: type: git url: https://github.com/ros-controls/realtime_tools.git - version: master + version: jazzy ros-controls/control_msgs: type: git url: https://github.com/ros-controls/control_msgs.git From f4e3f5a8ebf40aee63f896208d542dbc55e787c2 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 29 Jan 2025 19:55:08 +0100 Subject: [PATCH 02/26] Fix the initial wrong periodicity reported by controller_manager (#2018) --- controller_manager/src/ros2_control_node.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index 75a98d19dd..176c346b3f 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -93,6 +93,10 @@ int main(int argc, char ** argv) } } + // wait for the clock to be available + cm->get_clock()->wait_until_started(); + cm->get_clock()->sleep_for(rclcpp::Duration::from_seconds(1.0 / cm->get_update_rate())); + RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate()); const int thread_priority = cm->get_parameter_or("thread_priority", kSchedPriority); RCLCPP_INFO( @@ -122,7 +126,7 @@ int main(int argc, char ** argv) auto const period = std::chrono::nanoseconds(1'000'000'000 / cm->get_update_rate()); auto const cm_now = std::chrono::nanoseconds(cm->now().nanoseconds()); std::chrono::time_point - next_iteration_time{cm_now}; + next_iteration_time{cm_now - period}; // for calculating the measured period of the loop rclcpp::Time previous_time = cm->now() - period; From 882b489f8943af2bedb078ad1a733f62cd12800c Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 29 Jan 2025 20:05:58 +0100 Subject: [PATCH 03/26] Handle SIGINT properly in the controller manager (#2014) --- .../controller_manager/controller_manager.hpp | 9 ++- controller_manager/src/controller_manager.cpp | 63 +++++++++++++++++++ .../hardware_interface/resource_manager.hpp | 7 +++ hardware_interface/src/resource_manager.cpp | 18 +++++- 4 files changed, 95 insertions(+), 2 deletions(-) diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp index ba4bd2acaa..49eed135be 100644 --- a/controller_manager/include/controller_manager/controller_manager.hpp +++ b/controller_manager/include/controller_manager/controller_manager.hpp @@ -80,7 +80,13 @@ class ControllerManager : public rclcpp::Node const std::string & node_namespace = "", const rclcpp::NodeOptions & options = get_cm_node_options()); - virtual ~ControllerManager() = default; + virtual ~ControllerManager(); + + /// Shutdown all controllers in the controller manager. + /** + * \return true if all controllers are successfully shutdown, false otherwise. + */ + bool shutdown_controllers(); void robot_description_callback(const std_msgs::msg::String & msg); @@ -531,6 +537,7 @@ class ControllerManager : public rclcpp::Node int used_by_realtime_controllers_index_ = -1; }; + std::unique_ptr preshutdown_cb_handle_{nullptr}; RTControllerListWrapper rt_controllers_wrapper_; std::unordered_map controller_chain_spec_; std::vector ordered_controllers_names_; diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 110627dec1..bef2985c0b 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -291,6 +291,46 @@ ControllerManager::ControllerManager( init_controller_manager(); } +ControllerManager::~ControllerManager() +{ + if (preshutdown_cb_handle_) + { + rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context(); + context->remove_pre_shutdown_callback(*(preshutdown_cb_handle_.get())); + preshutdown_cb_handle_.reset(); + } +} + +bool ControllerManager::shutdown_controllers() +{ + RCLCPP_INFO(get_logger(), "Shutting down all controllers in the controller manager."); + // Shutdown all controllers + std::lock_guard guard(rt_controllers_wrapper_.controllers_lock_); + std::vector controllers_list = rt_controllers_wrapper_.get_updated_list(guard); + bool ctrls_shutdown_status = true; + for (auto & controller : controllers_list) + { + if (is_controller_active(controller.c)) + { + RCLCPP_INFO( + get_logger(), "Deactivating controller '%s'", controller.c->get_node()->get_name()); + controller.c->get_node()->deactivate(); + controller.c->release_interfaces(); + } + if (is_controller_inactive(*controller.c) || is_controller_unconfigured(*controller.c)) + { + RCLCPP_INFO( + get_logger(), "Shutting down controller '%s'", controller.c->get_node()->get_name()); + shutdown_controller(controller); + } + ctrls_shutdown_status &= + (controller.c->get_node()->get_current_state().id() == + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED); + executor_->remove_node(controller.c->get_node()->get_node_base_interface()); + } + return ctrls_shutdown_status; +} + void ControllerManager::init_controller_manager() { // Get parameters needed for RT "update" loop to work @@ -329,6 +369,29 @@ void ControllerManager::init_controller_manager() diagnostics_updater_.add( "Controller Manager Activity", this, &ControllerManager::controller_manager_diagnostic_callback); + + // Add on_shutdown callback to stop the controller manager + rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context(); + preshutdown_cb_handle_ = + std::make_unique(context->add_pre_shutdown_callback( + [this]() + { + RCLCPP_INFO(get_logger(), "Shutdown request received...."); + if (this->get_node_base_interface()->get_associated_with_executor_atomic().load()) + { + executor_->remove_node(this->get_node_base_interface()); + } + executor_->cancel(); + if (!this->shutdown_controllers()) + { + RCLCPP_ERROR(get_logger(), "Failed shutting down the controllers."); + } + if (!resource_manager_->shutdown_components()) + { + RCLCPP_ERROR(get_logger(), "Failed shutting down hardware components."); + } + RCLCPP_INFO(get_logger(), "Shutting down the controller manager."); + })); } void ControllerManager::initialize_parameters() diff --git a/hardware_interface/include/hardware_interface/resource_manager.hpp b/hardware_interface/include/hardware_interface/resource_manager.hpp index b67aba088d..06b8f51952 100644 --- a/hardware_interface/include/hardware_interface/resource_manager.hpp +++ b/hardware_interface/include/hardware_interface/resource_manager.hpp @@ -76,6 +76,13 @@ class ResourceManager virtual ~ResourceManager(); + /// Shutdown all hardware components, irrespective of their state. + /** + * The method is called when the controller manager is being shutdown. + * @return true if all hardware components are successfully shutdown, false otherwise. + */ + bool shutdown_components(); + /// Load resources from on a given URDF. /** * The resource manager can be post-initialized with a given URDF. diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index 7a616d890d..a99ae3db3b 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -573,7 +573,7 @@ class ResourceStorage result = shutdown_hardware(hardware); break; case State::PRIMARY_STATE_ACTIVE: - result = shutdown_hardware(hardware); + result = deactivate_hardware(hardware) && shutdown_hardware(hardware); break; case State::PRIMARY_STATE_FINALIZED: result = true; @@ -1040,6 +1040,22 @@ ResourceManager::ResourceManager( } } +bool ResourceManager::shutdown_components() +{ + std::unique_lock guard(resource_interfaces_lock_); + bool shutdown_status = true; + for (auto const & hw_info : resource_storage_->hardware_info_map_) + { + rclcpp_lifecycle::State finalized_state( + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED); + if (set_component_state(hw_info.first, finalized_state) != return_type::OK) + { + shutdown_status = false; + } + } + return shutdown_status; +} + // CM API: Called in "callback/slow"-thread bool ResourceManager::load_and_initialize_components( const std::string & urdf, const unsigned int update_rate) From 4f7ac1560eb07b3442cba3c728a289a1d102bc18 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Wed, 29 Jan 2025 19:16:02 +0000 Subject: [PATCH 04/26] Update changelogs --- controller_interface/CHANGELOG.rst | 6 ++++++ controller_manager/CHANGELOG.rst | 10 ++++++++++ controller_manager_msgs/CHANGELOG.rst | 3 +++ hardware_interface/CHANGELOG.rst | 5 +++++ hardware_interface_testing/CHANGELOG.rst | 3 +++ joint_limits/CHANGELOG.rst | 6 ++++++ ros2_control/CHANGELOG.rst | 3 +++ ros2_control_test_assets/CHANGELOG.rst | 3 +++ ros2controlcli/CHANGELOG.rst | 3 +++ rqt_controller_manager/CHANGELOG.rst | 3 +++ transmission_interface/CHANGELOG.rst | 3 +++ 11 files changed, 48 insertions(+) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index df7ae97d89..28e7475f34 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Use `target_compile_definitions` instead of installing test files (`#2009 `_) +* Add GPS semantic component (`#2000 `_) +* Contributors: Sai Kishor Kothakota, Wiktor Bajor + 4.24.0 (2025-01-13) ------------------- * Trigger shutdown transition in destructor (`#1979 `_) diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index ef709431c7..e6c81342f1 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Handle SIGINT properly in the controller manager (`#2014 `_) +* Fix the initial wrong periodicity reported by controller_manager (`#2018 `_) +* Use `target_compile_definitions` instead of installing test files (`#2009 `_) +* Fix a heading level (`#2007 `_) +* Update path of GPL (`#1994 `_) +* Fix: on_shutdown callback of controllers never get executed (`#1995 `_) +* Contributors: Christoph Fröhlich, Sai Kishor Kothakota, Wiktor Bajor + 4.24.0 (2025-01-13) ------------------- * [CM] Remove obsolete ControllerMock from the tests (`#1990 `_) diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 4bd5fa76c9..272a4515bd 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index f008335c1e..7c94af41fd 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Handle SIGINT properly in the controller manager (`#2014 `_) +* Contributors: Sai Kishor Kothakota + 4.24.0 (2025-01-13) ------------------- * Add missing link of mock_components to hardware_interface (`#1992 `_) diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index cc4c216dc5..0efc581980 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index c78bf55a1c..dfcfbb5ff4 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Define _USE_MATH_DEFINES in joint_soft_limiter.cpp to ensure that M_PI is defined (`#2001 `_) +* Use actual position when limiting desired position (`#1988 `_) +* Contributors: Sai Kishor Kothakota, Silvio Traversaro + 4.24.0 (2025-01-13) ------------------- * Return strong type for joint_limits helpers (`#1981 `_) diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index f179fd300b..89b4db5a8c 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index affd8f51f4..8bf682deb3 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 989e563d40..8523218ed9 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 53b7cd0444..2e1deb7fff 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 4150c6846b..20b26e0e29 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.24.0 (2025-01-13) ------------------- From 3755e03a7d87978307f059e6c5687f65eca1084c Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Wed, 29 Jan 2025 19:16:29 +0000 Subject: [PATCH 05/26] 4.25.0 --- controller_interface/CHANGELOG.rst | 4 ++-- controller_interface/package.xml | 2 +- controller_manager/CHANGELOG.rst | 4 ++-- controller_manager/package.xml | 2 +- controller_manager_msgs/CHANGELOG.rst | 4 ++-- controller_manager_msgs/package.xml | 2 +- hardware_interface/CHANGELOG.rst | 4 ++-- hardware_interface/package.xml | 2 +- hardware_interface_testing/CHANGELOG.rst | 4 ++-- hardware_interface_testing/package.xml | 2 +- joint_limits/CHANGELOG.rst | 4 ++-- joint_limits/package.xml | 2 +- ros2_control/CHANGELOG.rst | 4 ++-- ros2_control/package.xml | 2 +- ros2_control_test_assets/CHANGELOG.rst | 4 ++-- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 4 ++-- ros2controlcli/package.xml | 2 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 4 ++-- rqt_controller_manager/package.xml | 2 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 4 ++-- transmission_interface/package.xml | 2 +- 24 files changed, 35 insertions(+), 35 deletions(-) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index 28e7475f34..ce979b4fee 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- * Use `target_compile_definitions` instead of installing test files (`#2009 `_) * Add GPS semantic component (`#2000 `_) * Contributors: Sai Kishor Kothakota, Wiktor Bajor diff --git a/controller_interface/package.xml b/controller_interface/package.xml index d8de9b7a19..34144dc71d 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.24.0 + 4.25.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index e6c81342f1..c17f7981ec 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- * Handle SIGINT properly in the controller manager (`#2014 `_) * Fix the initial wrong periodicity reported by controller_manager (`#2018 `_) * Use `target_compile_definitions` instead of installing test files (`#2009 `_) diff --git a/controller_manager/package.xml b/controller_manager/package.xml index 61f9bceb55..cad0383937 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.24.0 + 4.25.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 272a4515bd..9304dfb813 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index 6af8412634..bce5c0de46 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.24.0 + 4.25.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 7c94af41fd..110e30ec12 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- * Handle SIGINT properly in the controller manager (`#2014 `_) * Contributors: Sai Kishor Kothakota diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index 45a7c6a2f4..af42890d98 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 4.24.0 + 4.25.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 0efc581980..4e3a608e09 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/hardware_interface_testing/package.xml b/hardware_interface_testing/package.xml index 35337fb87c..bc1e76d309 100644 --- a/hardware_interface_testing/package.xml +++ b/hardware_interface_testing/package.xml @@ -1,7 +1,7 @@ hardware_interface_testing - 4.24.0 + 4.25.0 ros2_control hardware interface testing Bence Magyar Denis Štogl diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index dfcfbb5ff4..1826e43211 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- * Define _USE_MATH_DEFINES in joint_soft_limiter.cpp to ensure that M_PI is defined (`#2001 `_) * Use actual position when limiting desired position (`#1988 `_) * Contributors: Sai Kishor Kothakota, Silvio Traversaro diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 38f81e87c3..479a2b5cba 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 4.24.0 + 4.25.0 Package with interfaces for handling of joint limits in controllers or in hardware. The package also implements Saturation Joint Limiter for position-velocity-acceleration set and other individual interfaces. Bence Magyar diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 89b4db5a8c..17996f13a1 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/ros2_control/package.xml b/ros2_control/package.xml index d917067328..7d8344db67 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 4.24.0 + 4.25.0 Metapackage for ROS2 control related packages Bence Magyar Denis Štogl diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index 8bf682deb3..c397d04da2 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index e58b60b41c..0565426847 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 4.24.0 + 4.25.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 8523218ed9..fdc0d87ffb 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index a2426f80a9..56e3501b71 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 4.24.0 + 4.25.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index f48bf95e15..568dcb4faa 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="4.24.0", + version="4.25.0", packages=find_packages(exclude=["test"]), data_files=[ ("share/" + package_name, ["package.xml"]), diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 2e1deb7fff..dbdf0fa4ce 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index 26719000f4..2cc29f2b01 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 4.24.0 + 4.25.0 Graphical frontend for interacting with the controller manager. Bence Magyar Denis Štogl diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index 6d221abc07..f8c6993bba 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -20,7 +20,7 @@ setup( name=package_name, - version="4.24.0", + version="4.25.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 20b26e0e29..850f5b91b6 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.25.0 (2025-01-29) +------------------- 4.24.0 (2025-01-13) ------------------- diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index d32c7f0655..c9a91f1a91 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 4.24.0 + 4.25.0 transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this. Bence Magyar Denis Štogl From 82621a185a50e823d9220bb0f5570ab8c3d97a3c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 29 Jan 2025 21:42:24 +0100 Subject: [PATCH 06/26] Use ABI workflow from ros2_control_ci (#2022) --- .github/workflows/humble-abi-compatibility.yml | 12 +++--------- .github/workflows/jazzy-abi-compatibility.yml | 12 +++--------- .github/workflows/rolling-abi-compatibility.yml | 12 +++--------- 3 files changed, 9 insertions(+), 27 deletions(-) diff --git a/.github/workflows/humble-abi-compatibility.yml b/.github/workflows/humble-abi-compatibility.yml index eed2a7589f..f4172ee3e6 100644 --- a/.github/workflows/humble-abi-compatibility.yml +++ b/.github/workflows/humble-abi-compatibility.yml @@ -21,12 +21,6 @@ concurrency: jobs: abi_check: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - - uses: ros-industrial/industrial_ci@master - env: - ROS_DISTRO: humble - ROS_REPO: testing - ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }} - NOT_TEST_BUILD: true + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-abi-check.yml@master + with: + ros_distro: humble diff --git a/.github/workflows/jazzy-abi-compatibility.yml b/.github/workflows/jazzy-abi-compatibility.yml index aa0fe81e63..83a81fec44 100644 --- a/.github/workflows/jazzy-abi-compatibility.yml +++ b/.github/workflows/jazzy-abi-compatibility.yml @@ -21,12 +21,6 @@ concurrency: jobs: abi_check: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - - uses: ros-industrial/industrial_ci@master - env: - ROS_DISTRO: jazzy - ROS_REPO: testing - ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }} - NOT_TEST_BUILD: true + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-abi-check.yml@master + with: + ros_distro: jazzy diff --git a/.github/workflows/rolling-abi-compatibility.yml b/.github/workflows/rolling-abi-compatibility.yml index 50f2a46154..02a38494b5 100644 --- a/.github/workflows/rolling-abi-compatibility.yml +++ b/.github/workflows/rolling-abi-compatibility.yml @@ -21,12 +21,6 @@ concurrency: jobs: abi_check: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - - uses: ros-industrial/industrial_ci@master - env: - ROS_DISTRO: rolling - ROS_REPO: testing - ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }} - NOT_TEST_BUILD: true + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-abi-check.yml@master + with: + ros_distro: rolling From 459a05f1f2f7bb4e453b6ad6861f52710533f8e1 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 1 Feb 2025 09:47:02 +0100 Subject: [PATCH 07/26] Bump version of pre-commit hooks (#2027) --- .pre-commit-config.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index feefcc317d..f469640d98 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -50,7 +50,7 @@ repos: args: ["--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404"] - repo: https://github.com/psf/black - rev: 24.10.0 + rev: 25.1.0 hooks: - id: black args: ["--line-length=99"] @@ -63,7 +63,7 @@ repos: # CPP hooks - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v19.1.5 + rev: v19.1.7 hooks: - id: clang-format args: ['-fallback-style=none', '-i'] @@ -126,14 +126,14 @@ repos: # Spellcheck in comments and docs # skipping of *.svg files is not working... - repo: https://github.com/codespell-project/codespell - rev: v2.3.0 + rev: v2.4.1 hooks: - id: codespell args: ['--write-changes', '--uri-ignore-words-list=ist', '-L manuel'] exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$ - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.30.0 + rev: 0.31.1 hooks: - id: check-github-workflows args: ["--verbose"] From 2dc37252af4b0b6ad4902bffab3458066dc7d376 Mon Sep 17 00:00:00 2001 From: Thibault Poignonec <79221188+tpoignonec@users.noreply.github.com> Date: Mon, 3 Feb 2025 11:33:37 +0100 Subject: [PATCH 08/26] add a semantic command interface to "semantic_components" (#1945) --- controller_interface/CMakeLists.txt | 20 +++- .../semantic_components/led_rgb_device.hpp | 77 +++++++++++++ .../semantic_component_command_interface.hpp | 103 ++++++++++++++++++ .../test/test_led_rgb_device.cpp | 87 +++++++++++++++ .../test/test_led_rgb_device.hpp | 63 +++++++++++ ...t_semantic_component_command_interface.cpp | 77 +++++++++++++ ...t_semantic_component_command_interface.hpp | 65 +++++++++++ doc/release_notes.rst | 2 + 8 files changed, 493 insertions(+), 1 deletion(-) create mode 100644 controller_interface/include/semantic_components/led_rgb_device.hpp create mode 100644 controller_interface/include/semantic_components/semantic_component_command_interface.hpp create mode 100644 controller_interface/test/test_led_rgb_device.cpp create mode 100644 controller_interface/test/test_led_rgb_device.hpp create mode 100644 controller_interface/test/test_semantic_component_command_interface.cpp create mode 100644 controller_interface/test/test_semantic_component_command_interface.hpp diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 10604a5255..bfd12dae60 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -87,12 +87,30 @@ if(BUILD_TESTING) ament_target_dependencies(test_pose_sensor geometry_msgs ) - ament_add_gmock(test_gps_sensor test/test_gps_sensor.cpp) target_link_libraries(test_gps_sensor controller_interface hardware_interface::hardware_interface ) + + # Semantic component command interface tests + + ament_add_gmock(test_semantic_component_command_interface + test/test_semantic_component_command_interface.cpp + ) + target_link_libraries(test_semantic_component_command_interface + controller_interface + hardware_interface::hardware_interface + ) + + ament_add_gmock(test_led_rgb_device test/test_led_rgb_device.cpp) + target_link_libraries(test_led_rgb_device + controller_interface + hardware_interface::hardware_interface + ) + ament_target_dependencies(test_led_rgb_device + std_msgs + ) endif() install( diff --git a/controller_interface/include/semantic_components/led_rgb_device.hpp b/controller_interface/include/semantic_components/led_rgb_device.hpp new file mode 100644 index 0000000000..0ecbd1e93d --- /dev/null +++ b/controller_interface/include/semantic_components/led_rgb_device.hpp @@ -0,0 +1,77 @@ +// Copyright (c) 2024, Sherpa Mobile Robotics +// +// 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 SEMANTIC_COMPONENTS__LED_RGB_DEVICE_HPP_ +#define SEMANTIC_COMPONENTS__LED_RGB_DEVICE_HPP_ + +#include +#include + +#include "semantic_components/semantic_component_command_interface.hpp" +#include "std_msgs/msg/color_rgba.hpp" + +namespace semantic_components +{ +class LedRgbDevice : public SemanticComponentCommandInterface +{ +public: + /** + * Constructor for a LED RGB device with interface names set based on device name. + * The constructor sets the command interface names to "/interface_r", + * "/interface_g", "/interface_b". + * + * \param[in] name name of the LED device, used as a prefix for the command interface names + * \param[in] interface_r name of the command interface for the red channel + * \param[in] interface_g name of the command interface for the green channel + * \param[in] interface_b name of the command interface for the blue channel + */ + explicit LedRgbDevice( + const std::string & name, const std::string & interface_r, const std::string & interface_g, + const std::string & interface_b) + : SemanticComponentCommandInterface( + name, {{name + "/" + interface_r}, {name + "/" + interface_g}, {name + "/" + interface_b}}) + { + } + + /// Set LED states from ColorRGBA message + + /** + * Set the values of the LED RGB device from a ColorRGBA message. + * + * \details Sets the values of the red, green, and blue channels from the message. + * If any of the values are out of the range [0, 1], the function fails and returns false. + * + * \param[in] message ColorRGBA message + * + * \return true if all values were set, false otherwise + */ + bool set_values_from_message(const std_msgs::msg::ColorRGBA & message) override + { + if ( + message.r < 0 || message.r > 1 || message.g < 0 || message.g > 1 || message.b < 0 || + message.b > 1) + { + return false; + } + bool all_set = true; + all_set &= command_interfaces_[0].get().set_value(message.r); + all_set &= command_interfaces_[1].get().set_value(message.g); + all_set &= command_interfaces_[2].get().set_value(message.b); + return all_set; + } +}; + +} // namespace semantic_components + +#endif // SEMANTIC_COMPONENTS__LED_RGB_DEVICE_HPP_ diff --git a/controller_interface/include/semantic_components/semantic_component_command_interface.hpp b/controller_interface/include/semantic_components/semantic_component_command_interface.hpp new file mode 100644 index 0000000000..5569b7ba9d --- /dev/null +++ b/controller_interface/include/semantic_components/semantic_component_command_interface.hpp @@ -0,0 +1,103 @@ +// Copyright (c) 2024, Sherpa Mobile Robotics +// +// 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 SEMANTIC_COMPONENTS__SEMANTIC_COMPONENT_COMMAND_INTERFACE_HPP_ +#define SEMANTIC_COMPONENTS__SEMANTIC_COMPONENT_COMMAND_INTERFACE_HPP_ + +#include +#include + +#include "controller_interface/helpers.hpp" +#include "hardware_interface/loaned_command_interface.hpp" + +namespace semantic_components +{ +template +class SemanticComponentCommandInterface +{ +public: + SemanticComponentCommandInterface( + const std::string & name, const std::vector & interface_names) + : name_(name), interface_names_(interface_names) + { + assert(interface_names.size() > 0); + command_interfaces_.reserve(interface_names.size()); + } + + virtual ~SemanticComponentCommandInterface() = default; + + /// Assign loaned command interfaces from the hardware. + /** + * Assign loaned command interfaces on the controller start. + * + * \param[in] command_interfaces vector of command interfaces provided by the controller. + */ + bool assign_loaned_command_interfaces( + std::vector & command_interfaces) + { + return controller_interface::get_ordered_interfaces( + command_interfaces, interface_names_, "", command_interfaces_); + } + + /// Release loaned command interfaces from the hardware. + void release_interfaces() { command_interfaces_.clear(); } + + /// Definition of command interface names for the component. + /** + * The function should be used in "command_interface_configuration()" of a controller to provide + * standardized command interface names semantic component. + * + * \default Default implementation defined command interfaces as "name/NR" where NR is number + * from 0 to size of values; + * \return list of strings with command interface names for the semantic component. + */ + const std::vector & get_command_interface_names() const { return interface_names_; } + + /// Return all values. + /** + * \return true if it gets all the values, else false (i.e., invalid size or if the method + * ``hardware_interface::LoanedCommandInterface::set_value`` fails). + */ + bool set_values(const std::vector & values) + { + // check we have sufficient memory + if (values.size() != command_interfaces_.size()) + { + return false; + } + // set values + bool all_set = true; + for (auto i = 0u; i < values.size(); ++i) + { + all_set &= command_interfaces_[i].get().set_value(values[i]); + } + return all_set; + } + + /// Set values from MessageInputType + /** + * \return True if all values were set successfully, false otherwise. + */ + virtual bool set_values_from_message(const MessageInputType & /* message */) = 0; + +protected: + std::string name_; + std::vector interface_names_; + std::vector> + command_interfaces_; +}; + +} // namespace semantic_components + +#endif // SEMANTIC_COMPONENTS__SEMANTIC_COMPONENT_COMMAND_INTERFACE_HPP_ diff --git a/controller_interface/test/test_led_rgb_device.cpp b/controller_interface/test/test_led_rgb_device.cpp new file mode 100644 index 0000000000..afef78b489 --- /dev/null +++ b/controller_interface/test/test_led_rgb_device.cpp @@ -0,0 +1,87 @@ +// Copyright (c) 2024, Sherpa Mobile Robotics +// +// 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 "test_led_rgb_device.hpp" + +void LedDeviceTest::SetUp() +{ + full_cmd_interface_names_.reserve(size_); + for (const auto & interface_name : interface_names_) + { + full_cmd_interface_names_.emplace_back(device_name_ + '/' + interface_name); + } +} + +void LedDeviceTest::TearDown() { led_device_.reset(nullptr); } + +TEST_F(LedDeviceTest, validate_all) +{ + // Create device + led_device_ = std::make_unique( + device_name_, interface_names_[0], interface_names_[1], interface_names_[2]); + EXPECT_EQ(led_device_->name_, device_name_); + + // Validate reserved space for interface_names_ and command_interfaces_ + // As command_interfaces_ are not defined yet, use capacity() + ASSERT_EQ(led_device_->interface_names_.size(), size_); + ASSERT_EQ(led_device_->command_interfaces_.capacity(), size_); + + // Validate default interface_names_ + EXPECT_TRUE(std::equal( + led_device_->interface_names_.cbegin(), led_device_->interface_names_.cend(), + full_cmd_interface_names_.cbegin(), full_cmd_interface_names_.cend())); + + // Get interface names + std::vector interface_names = led_device_->get_command_interface_names(); + + // Assign values to position + hardware_interface::CommandInterface led_r{device_name_, interface_names_[0], &led_values_[0]}; + hardware_interface::CommandInterface led_g{device_name_, interface_names_[1], &led_values_[1]}; + hardware_interface::CommandInterface led_b{device_name_, interface_names_[2], &led_values_[2]}; + + // Create command interface vector in jumbled order + std::vector temp_command_interfaces; + temp_command_interfaces.reserve(3); + temp_command_interfaces.emplace_back(led_r); + temp_command_interfaces.emplace_back(led_g); + temp_command_interfaces.emplace_back(led_b); + + // Assign interfaces + led_device_->assign_loaned_command_interfaces(temp_command_interfaces); + EXPECT_EQ(led_device_->command_interfaces_.size(), size_); + + // Validate correct assignment + const std::vector test_led_values_cmd = {0.1, 0.2, 0.3}; + EXPECT_TRUE(led_device_->set_values(test_led_values_cmd)); + + EXPECT_EQ(led_values_[0], test_led_values_cmd[0]); + EXPECT_EQ(led_values_[1], test_led_values_cmd[1]); + EXPECT_EQ(led_values_[2], test_led_values_cmd[2]); + + // Validate correct assignment from message + std_msgs::msg::ColorRGBA temp_message; + temp_message.r = static_cast(test_led_values_cmd[0]); + temp_message.g = static_cast(test_led_values_cmd[1]); + temp_message.b = static_cast(test_led_values_cmd[2]); + EXPECT_TRUE(led_device_->set_values_from_message(temp_message)); + + double float_tolerance = 1e-6; + EXPECT_NEAR(led_values_[0], test_led_values_cmd[0], float_tolerance); + EXPECT_NEAR(led_values_[1], test_led_values_cmd[1], float_tolerance); + EXPECT_NEAR(led_values_[2], test_led_values_cmd[2], float_tolerance); + + // Release command interfaces + led_device_->release_interfaces(); + ASSERT_EQ(led_device_->command_interfaces_.size(), 0); +} diff --git a/controller_interface/test/test_led_rgb_device.hpp b/controller_interface/test/test_led_rgb_device.hpp new file mode 100644 index 0000000000..393a8323d6 --- /dev/null +++ b/controller_interface/test/test_led_rgb_device.hpp @@ -0,0 +1,63 @@ +// Copyright (c) 2024, Sherpa Mobile Robotics +// +// 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 TEST_LED_RGB_DEVICE_HPP_ +#define TEST_LED_RGB_DEVICE_HPP_ + +#include + +#include +#include +#include +#include +#include + +#include "semantic_components/led_rgb_device.hpp" + +class TestableLedDevice : public semantic_components::LedRgbDevice +{ + FRIEND_TEST(LedDeviceTest, validate_all); + +public: + TestableLedDevice( + const std::string & name, const std::string & interface_r, const std::string & interface_g, + const std::string & interface_b) + : LedRgbDevice{name, interface_r, interface_g, interface_b} + { + } + + virtual ~TestableLedDevice() = default; +}; + +class LedDeviceTest : public ::testing::Test +{ +public: + void SetUp(); + void TearDown(); + +protected: + const size_t size_ = 3; + const std::string device_name_ = "test_led_device"; + + std::vector full_cmd_interface_names_; + const std::vector interface_names_ = {"r", "g", "b"}; + + std::array led_values_ = { + {std::numeric_limits::quiet_NaN(), std::numeric_limits::quiet_NaN(), + std::numeric_limits::quiet_NaN()}}; + + std::unique_ptr led_device_; +}; + +#endif // TEST_LED_RGB_DEVICE_HPP_ diff --git a/controller_interface/test/test_semantic_component_command_interface.cpp b/controller_interface/test/test_semantic_component_command_interface.cpp new file mode 100644 index 0000000000..ce8de65c7f --- /dev/null +++ b/controller_interface/test/test_semantic_component_command_interface.cpp @@ -0,0 +1,77 @@ +// Copyright 2024 Sherpa Mobile Robotics +// 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. + +/* + * Authors: Thibault Poignonec + */ + +#include "test_semantic_component_command_interface.hpp" + +#include +#include +#include +#include + +void SemanticCommandInterfaceTest::TearDown() { semantic_component_.reset(nullptr); } + +TEST_F(SemanticCommandInterfaceTest, validate_command_interfaces) +{ + // create 'test_component' with 3 interfaces using default naming + // e.g. test_component_1, test_component_2 so on... + semantic_component_ = std::make_unique(component_name_); + + // generate the interface_names_ + std::vector interface_names = semantic_component_->get_command_interface_names(); + + // validate assign_loaned_command_interfaces + // create interfaces and assign values to it + std::vector interface_values = { + std::numeric_limits::quiet_NaN(), std::numeric_limits::quiet_NaN(), + std::numeric_limits::quiet_NaN()}; + hardware_interface::CommandInterface cmd_interface_1{component_name_, "1", &interface_values[0]}; + hardware_interface::CommandInterface cmd_interface_2{component_name_, "2", &interface_values[1]}; + hardware_interface::CommandInterface cmd_interface_3{component_name_, "3", &interface_values[2]}; + + // create local command interface vector + std::vector temp_command_interfaces; + temp_command_interfaces.reserve(3); + // insert the interfaces in jumbled sequence + temp_command_interfaces.emplace_back(cmd_interface_1); + temp_command_interfaces.emplace_back(cmd_interface_3); + temp_command_interfaces.emplace_back(cmd_interface_2); + + // now call the function to make them in order like interface_names + EXPECT_TRUE(semantic_component_->assign_loaned_command_interfaces(temp_command_interfaces)); + + // validate the count of command_interfaces_ + ASSERT_EQ(semantic_component_->command_interfaces_.size(), 3u); + + // Validate correct assignment + const std::vector test_cmd_values = {0.1, 0.2, 0.3}; + EXPECT_TRUE(semantic_component_->set_values(test_cmd_values)); + + EXPECT_EQ(interface_values[0], test_cmd_values[0]); + EXPECT_EQ(interface_values[1], test_cmd_values[1]); + EXPECT_EQ(interface_values[2], test_cmd_values[2]); + + // release the state_interfaces_ + semantic_component_->release_interfaces(); + + // validate the count of state_interfaces_ + ASSERT_EQ(semantic_component_->command_interfaces_.size(), 0u); + + // validate that release_interfaces() does not touch interface_names_ + ASSERT_TRUE(std::equal( + semantic_component_->interface_names_.begin(), semantic_component_->interface_names_.end(), + interface_names.begin(), interface_names.end())); +} diff --git a/controller_interface/test/test_semantic_component_command_interface.hpp b/controller_interface/test/test_semantic_component_command_interface.hpp new file mode 100644 index 0000000000..df1cb3a411 --- /dev/null +++ b/controller_interface/test/test_semantic_component_command_interface.hpp @@ -0,0 +1,65 @@ +// Copyright 2024 Sherpa Mobile Robotics +// 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. + +/* + * Authors: Thibault Poignonec + */ + +#ifndef TEST_SEMANTIC_COMPONENT_COMMAND_INTERFACE_HPP_ +#define TEST_SEMANTIC_COMPONENT_COMMAND_INTERFACE_HPP_ + +#include + +#include +#include + +#include "geometry_msgs/msg/pose.hpp" +#include "semantic_components/semantic_component_command_interface.hpp" + +// implementing and friending so we can access member variables +class TestableSemanticCommandInterface +: public semantic_components::SemanticComponentCommandInterface +{ + FRIEND_TEST(SemanticCommandInterfaceTest, validate_custom_names); + FRIEND_TEST(SemanticCommandInterfaceTest, validate_command_interfaces); + +public: + explicit TestableSemanticCommandInterface(const std::string & name) + : SemanticComponentCommandInterface(name, {name + "/1", name + "/2", name + "/3"}) + { + } + + virtual ~TestableSemanticCommandInterface() = default; + + // We are not testing the implementation of the function, so we simply return false. + // Note that set_values_from_message is a pure virtual function, hence the need for this + bool set_values_from_message(const geometry_msgs::msg::Pose & /* message */) override + { + return false; + } + + std::string test_name_ = "TestSemanticCommandInterface"; +}; + +class SemanticCommandInterfaceTest : public ::testing::Test +{ +public: + void TearDown(); + +protected: + const std::string component_name_ = "test_component"; + const size_t size_ = 3; + std::unique_ptr semantic_component_; +}; + +#endif // TEST_SEMANTIC_COMPONENT_COMMAND_INTERFACE_HPP_ diff --git a/doc/release_notes.rst b/doc/release_notes.rst index 58930ec6c4..3dec704f23 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -27,6 +27,8 @@ For details see the controller_manager section. * The ``assign_interfaces`` and ``release_interfaces`` methods are now virtual, so that the user can override them to store the interfaces into custom variable types, so that the user can have the flexibility to take the ownership of the loaned interfaces to the controller (`#1743 `_) * The new ``PoseSensor`` semantic component provides a standard interface for hardware providing cartesian poses (`#1775 `_) * The controllers now support the fallback controllers (a list of controllers that will be activated, when the spawned controllers fails by throwing an exception or returning ``return_type::ERROR`` during the ``update`` cycle) (`#1789 `_) +* A new ``SemanticComponentCommandInterface`` semantic component provides capabilities analogous to the ``SemanticComponentInterface``, but for write-only devices (`#1945 `_) +* The new semantic command interface ``LedRgbDevice`` provides standard (command) interfaces for 3-channel LED devices (`#1945 `_) controller_manager ****************** From 32d1508cd103d1eff4e68696bd0944ee31309edd Mon Sep 17 00:00:00 2001 From: "Dr. Denis" Date: Tue, 4 Feb 2025 14:42:10 +0100 Subject: [PATCH 09/26] [Doc] Fix broken link. (#2034) --- hardware_interface/doc/writing_new_hardware_component.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/hardware_interface/doc/writing_new_hardware_component.rst b/hardware_interface/doc/writing_new_hardware_component.rst index 9a7f2fe625..f899b60236 100644 --- a/hardware_interface/doc/writing_new_hardware_component.rst +++ b/hardware_interface/doc/writing_new_hardware_component.rst @@ -165,6 +165,6 @@ That's it! Enjoy writing great controllers! Useful External References --------------------------- -- `Templates and scripts for generating controllers shell `_ +- `Templates and scripts for generating controllers shell `_ - .. NOTE:: The script is currently only recommended to use for Foxy, not compatible with the API from Galactic and onwards. + .. NOTE:: The script is currently only recommended to use with Foxy and Humble, not compatible with the API from Jazzy and onwards. From a91619ed4e10dc36b37f170bf8a3ceb72a7ee6d4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Tue, 4 Feb 2025 19:44:52 +0100 Subject: [PATCH 10/26] Semantic components docs (#2032) --- .../doc/asynchronous_components.rst | 2 +- .../doc/hardware_components_userdoc.rst | 1 + .../doc/hardware_interface_types_userdoc.rst | 5 +---- .../doc/semantic_components.rst | 20 +++++++++++++++++++ 4 files changed, 23 insertions(+), 5 deletions(-) create mode 100644 hardware_interface/doc/semantic_components.rst diff --git a/hardware_interface/doc/asynchronous_components.rst b/hardware_interface/doc/asynchronous_components.rst index c73281c3fe..d0a8f1ed2c 100644 --- a/hardware_interface/doc/asynchronous_components.rst +++ b/hardware_interface/doc/asynchronous_components.rst @@ -1,4 +1,4 @@ -:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/different_update_rates_userdoc.rst +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/asynchronous_components.rst .. _asynchronous_components: diff --git a/hardware_interface/doc/hardware_components_userdoc.rst b/hardware_interface/doc/hardware_components_userdoc.rst index 3870433ef0..6b6d40914b 100644 --- a/hardware_interface/doc/hardware_components_userdoc.rst +++ b/hardware_interface/doc/hardware_components_userdoc.rst @@ -18,6 +18,7 @@ Guidelines and Best Practices Writing a Hardware Component Different Update Rates Asynchronous Execution + Semantic Components Handling of errors that happen during read() and write() calls diff --git a/hardware_interface/doc/hardware_interface_types_userdoc.rst b/hardware_interface/doc/hardware_interface_types_userdoc.rst index 45141e5479..f0b7ce36ae 100644 --- a/hardware_interface/doc/hardware_interface_types_userdoc.rst +++ b/hardware_interface/doc/hardware_interface_types_userdoc.rst @@ -54,10 +54,7 @@ Sensors ***************************** ````-tag groups multiple state interfaces describing, e.g., internal states of hardware. -Depending on the type of sensor, there exist a couple of specific semantic components with broadcasters shipped with ros2_controllers, e.g. - -- :ref:`Imu Sensor Broadcaster ` -- :ref:`Force Torque Sensor Broadcaster ` +Depending on the type of sensor, there exist a couple of specific semantic components with broadcasters shipped with ros2_controllers, see details in the :ref:`semantic_components `. GPIOs ***************************** diff --git a/hardware_interface/doc/semantic_components.rst b/hardware_interface/doc/semantic_components.rst new file mode 100644 index 0000000000..1991270170 --- /dev/null +++ b/hardware_interface/doc/semantic_components.rst @@ -0,0 +1,20 @@ +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/semantic_components.rst + +.. _semantic_components: + +Semantic Components +--------------------------------------------------------- + +In order to streamline the configuration of commonly used hardware interface, so-called semantic components can be used to wrap mechanisms to claim / release the interfaces. The base components ``semantic_components::SemanticComponentInterface`` and ``semantic_components::SemanticComponentCommandInterface`` are used to define semantic components for read-only and write-only devices, respectively. + +List of existing ``SemanticComponentInterface`` `(link to header file) `__ and associated broadcaster, if any: + + * `IMUSensor `__, used by :ref:`IMU Sensor Broadcaster ` + * `ForceTorqueSensor `__, used by :ref:`Force Torque Sensor Broadcaster ` + * `GPSSensor `__ + * `PoseSensor `__, used by :ref:`Pose Broadcaster ` + * `RangeSensor `__, used by :ref:`Range Sensor Broadcaster ` + +List of existing ``SemanticComponentCommandInterface`` `(link to header file) `__ and associated controller, if any: + + * `LedRgbDevice `__ From dab91b1a6d46feb422cb3e2b147096cb28d89f0d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 5 Feb 2025 16:53:58 +0100 Subject: [PATCH 11/26] Slightly increase timeout of test_spawner_unspawner (#2037) --- controller_manager/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index e704393022..d5bc3751d4 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -193,7 +193,7 @@ if(BUILD_TESTING) ament_add_gmock(test_spawner_unspawner test/test_spawner_unspawner.cpp - TIMEOUT 120 + TIMEOUT 180 ) target_link_libraries(test_spawner_unspawner controller_manager From 7406bdcc2e563202837bf95e65abcf963a898a97 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 7 Feb 2025 10:45:53 +0100 Subject: [PATCH 12/26] Fix memory leak in the ros2_control (#2033) --- .../include/hardware_interface/actuator.hpp | 4 ++-- .../hardware_interface/actuator_interface.hpp | 4 ++-- .../include/hardware_interface/hardware_info.hpp | 6 +++--- .../include/hardware_interface/sensor.hpp | 4 ++-- .../hardware_interface/sensor_interface.hpp | 4 ++-- .../include/hardware_interface/system.hpp | 4 ++-- .../hardware_interface/system_interface.hpp | 4 ++-- hardware_interface/src/actuator.cpp | 4 ++-- hardware_interface/src/sensor.cpp | 4 ++-- hardware_interface/src/system.cpp | 4 ++-- .../test/test_component_interfaces.cpp | 16 ---------------- .../test_component_interfaces_custom_export.cpp | 6 ------ .../test/test_resource_manager.cpp | 2 -- 13 files changed, 21 insertions(+), 45 deletions(-) diff --git a/hardware_interface/include/hardware_interface/actuator.hpp b/hardware_interface/include/hardware_interface/actuator.hpp index e5c23a68d3..aab829089a 100644 --- a/hardware_interface/include/hardware_interface/actuator.hpp +++ b/hardware_interface/include/hardware_interface/actuator.hpp @@ -72,9 +72,9 @@ class Actuator final const std::vector & start_interfaces, const std::vector & stop_interfaces); - std::string get_name() const; + const std::string & get_name() const; - std::string get_group_name() const; + const std::string & get_group_name() const; const rclcpp_lifecycle::State & get_lifecycle_state() const; diff --git a/hardware_interface/include/hardware_interface/actuator_interface.hpp b/hardware_interface/include/hardware_interface/actuator_interface.hpp index 6f4dfa4402..87b5202734 100644 --- a/hardware_interface/include/hardware_interface/actuator_interface.hpp +++ b/hardware_interface/include/hardware_interface/actuator_interface.hpp @@ -461,13 +461,13 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod /** * \return name. */ - virtual std::string get_name() const { return info_.name; } + const std::string & get_name() const { return info_.name; } /// Get name of the actuator hardware group to which it belongs to. /** * \return group name. */ - virtual std::string get_group_name() const { return info_.group; } + const std::string & get_group_name() const { return info_.group; } /// Get life-cycle state of the actuator hardware. /** diff --git a/hardware_interface/include/hardware_interface/hardware_info.hpp b/hardware_interface/include/hardware_interface/hardware_info.hpp index 9d96190954..6349baeb53 100644 --- a/hardware_interface/include/hardware_interface/hardware_info.hpp +++ b/hardware_interface/include/hardware_interface/hardware_info.hpp @@ -158,11 +158,11 @@ struct InterfaceDescription */ std::string interface_name; - std::string get_prefix_name() const { return prefix_name; } + const std::string & get_prefix_name() const { return prefix_name; } - std::string get_interface_name() const { return interface_info.name; } + const std::string & get_interface_name() const { return interface_info.name; } - std::string get_name() const { return interface_name; } + const std::string & get_name() const { return interface_name; } }; /// This structure stores information about hardware defined in a robot's URDF. diff --git a/hardware_interface/include/hardware_interface/sensor.hpp b/hardware_interface/include/hardware_interface/sensor.hpp index 26e99f032a..e47e34c0d7 100644 --- a/hardware_interface/include/hardware_interface/sensor.hpp +++ b/hardware_interface/include/hardware_interface/sensor.hpp @@ -62,9 +62,9 @@ class Sensor final std::vector export_state_interfaces(); - std::string get_name() const; + const std::string & get_name() const; - std::string get_group_name() const; + const std::string & get_group_name() const; const rclcpp_lifecycle::State & get_lifecycle_state() const; diff --git a/hardware_interface/include/hardware_interface/sensor_interface.hpp b/hardware_interface/include/hardware_interface/sensor_interface.hpp index 93de2a6494..c99138fc11 100644 --- a/hardware_interface/include/hardware_interface/sensor_interface.hpp +++ b/hardware_interface/include/hardware_interface/sensor_interface.hpp @@ -275,13 +275,13 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI /** * \return name. */ - virtual std::string get_name() const { return info_.name; } + const std::string & get_name() const { return info_.name; } /// Get name of the actuator hardware group to which it belongs to. /** * \return group name. */ - virtual std::string get_group_name() const { return info_.group; } + const std::string & get_group_name() const { return info_.group; } /// Get life-cycle state of the actuator hardware. /** diff --git a/hardware_interface/include/hardware_interface/system.hpp b/hardware_interface/include/hardware_interface/system.hpp index fc482d8106..750cbb301a 100644 --- a/hardware_interface/include/hardware_interface/system.hpp +++ b/hardware_interface/include/hardware_interface/system.hpp @@ -72,9 +72,9 @@ class System final const std::vector & start_interfaces, const std::vector & stop_interfaces); - std::string get_name() const; + const std::string & get_name() const; - std::string get_group_name() const; + const std::string & get_group_name() const; const rclcpp_lifecycle::State & get_lifecycle_state() const; diff --git a/hardware_interface/include/hardware_interface/system_interface.hpp b/hardware_interface/include/hardware_interface/system_interface.hpp index e145deae5b..4337f5fd19 100644 --- a/hardware_interface/include/hardware_interface/system_interface.hpp +++ b/hardware_interface/include/hardware_interface/system_interface.hpp @@ -490,13 +490,13 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI /** * \return name. */ - virtual std::string get_name() const { return info_.name; } + const std::string & get_name() const { return info_.name; } /// Get name of the actuator hardware group to which it belongs to. /** * \return group name. */ - virtual std::string get_group_name() const { return info_.group; } + const std::string & get_group_name() const { return info_.group; } /// Get life-cycle state of the actuator hardware. /** diff --git a/hardware_interface/src/actuator.cpp b/hardware_interface/src/actuator.cpp index 81bebf1182..790898cfed 100644 --- a/hardware_interface/src/actuator.cpp +++ b/hardware_interface/src/actuator.cpp @@ -277,9 +277,9 @@ return_type Actuator::perform_command_mode_switch( return impl_->perform_command_mode_switch(start_interfaces, stop_interfaces); } -std::string Actuator::get_name() const { return impl_->get_name(); } +const std::string & Actuator::get_name() const { return impl_->get_name(); } -std::string Actuator::get_group_name() const { return impl_->get_group_name(); } +const std::string & Actuator::get_group_name() const { return impl_->get_group_name(); } const rclcpp_lifecycle::State & Actuator::get_lifecycle_state() const { diff --git a/hardware_interface/src/sensor.cpp b/hardware_interface/src/sensor.cpp index ae4d930bbe..0ef4da36d4 100644 --- a/hardware_interface/src/sensor.cpp +++ b/hardware_interface/src/sensor.cpp @@ -233,9 +233,9 @@ std::vector Sensor::export_state_interfaces() // END: for backward compatibility } -std::string Sensor::get_name() const { return impl_->get_name(); } +const std::string & Sensor::get_name() const { return impl_->get_name(); } -std::string Sensor::get_group_name() const { return impl_->get_group_name(); } +const std::string & Sensor::get_group_name() const { return impl_->get_group_name(); } const rclcpp_lifecycle::State & Sensor::get_lifecycle_state() const { diff --git a/hardware_interface/src/system.cpp b/hardware_interface/src/system.cpp index 89d6afd42e..694e45f2f3 100644 --- a/hardware_interface/src/system.cpp +++ b/hardware_interface/src/system.cpp @@ -275,9 +275,9 @@ return_type System::perform_command_mode_switch( return impl_->perform_command_mode_switch(start_interfaces, stop_interfaces); } -std::string System::get_name() const { return impl_->get_name(); } +const std::string & System::get_name() const { return impl_->get_name(); } -std::string System::get_group_name() const { return impl_->get_group_name(); } +const std::string & System::get_group_name() const { return impl_->get_group_name(); } const rclcpp_lifecycle::State & System::get_lifecycle_state() const { diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index 28a74aeb66..06ef8a0e42 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -101,8 +101,6 @@ class DummyActuator : public hardware_interface::ActuatorInterface return command_interfaces; } - std::string get_name() const override { return "DummyActuator"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -193,8 +191,6 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface return CallbackReturn::SUCCESS; } - std::string get_name() const override { return "DummyActuatorDefault"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -276,8 +272,6 @@ class DummySensor : public hardware_interface::SensorInterface return state_interfaces; } - std::string get_name() const override { return "DummySensor"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -337,8 +331,6 @@ class DummySensorDefault : public hardware_interface::SensorInterface return CallbackReturn::SUCCESS; } - std::string get_name() const override { return "DummySensorDefault"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -397,8 +389,6 @@ class DummySensorJointDefault : public hardware_interface::SensorInterface return CallbackReturn::SUCCESS; } - std::string get_name() const override { return "DummySensorJointDefault"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -502,8 +492,6 @@ class DummySystem : public hardware_interface::SystemInterface return command_interfaces; } - std::string get_name() const override { return "DummySystem"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -608,8 +596,6 @@ class DummySystemDefault : public hardware_interface::SystemInterface return CallbackReturn::SUCCESS; } - std::string get_name() const override { return "DummySystemDefault"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { @@ -687,8 +673,6 @@ class DummySystemPreparePerform : public hardware_interface::SystemInterface return CallbackReturn::SUCCESS; } - std::string get_name() const override { return "DummySystemPreparePerform"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index 62e2b703cf..7335f9420a 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -54,8 +54,6 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface class DummyActuatorDefault : public hardware_interface::ActuatorInterface { - std::string get_name() const override { return "DummyActuatorDefault"; } - std::vector export_unlisted_state_interface_descriptions() override { @@ -95,8 +93,6 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface class DummySensorDefault : public hardware_interface::SensorInterface { - std::string get_name() const override { return "DummySensorDefault"; } - std::vector export_unlisted_state_interface_descriptions() override { @@ -118,8 +114,6 @@ class DummySensorDefault : public hardware_interface::SensorInterface class DummySystemDefault : public hardware_interface::SystemInterface { - std::string get_name() const override { return "DummySystemDefault"; } - std::vector export_unlisted_state_interface_descriptions() override { diff --git a/hardware_interface_testing/test/test_resource_manager.cpp b/hardware_interface_testing/test/test_resource_manager.cpp index be9e672b3b..65735e23f7 100644 --- a/hardware_interface_testing/test/test_resource_manager.cpp +++ b/hardware_interface_testing/test/test_resource_manager.cpp @@ -371,8 +371,6 @@ class ExternalComponent : public hardware_interface::ActuatorInterface return command_interfaces; } - std::string get_name() const override { return "ExternalComponent"; } - hardware_interface::return_type read( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { From 6da7986dbb1eb40bbf40996d86e6d47f2c5cadb9 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Fri, 7 Feb 2025 13:00:25 +0000 Subject: [PATCH 13/26] Update changelogs --- controller_interface/CHANGELOG.rst | 5 +++++ controller_manager/CHANGELOG.rst | 5 +++++ controller_manager_msgs/CHANGELOG.rst | 3 +++ hardware_interface/CHANGELOG.rst | 7 +++++++ hardware_interface_testing/CHANGELOG.rst | 5 +++++ joint_limits/CHANGELOG.rst | 3 +++ ros2_control/CHANGELOG.rst | 3 +++ ros2_control_test_assets/CHANGELOG.rst | 3 +++ ros2controlcli/CHANGELOG.rst | 3 +++ rqt_controller_manager/CHANGELOG.rst | 3 +++ transmission_interface/CHANGELOG.rst | 3 +++ 11 files changed, 43 insertions(+) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index ce979b4fee..d771f18d41 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* add a semantic command interface to "semantic_components" (`#1945 `_) +* Contributors: Thibault Poignonec + 4.25.0 (2025-01-29) ------------------- * Use `target_compile_definitions` instead of installing test files (`#2009 `_) diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index c17f7981ec..6c0a139cb0 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Slightly increase timeout of test_spawner_unspawner (`#2037 `_) +* Contributors: Christoph Fröhlich + 4.25.0 (2025-01-29) ------------------- * Handle SIGINT properly in the controller manager (`#2014 `_) diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 9304dfb813..e5629e91c6 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 110e30ec12..ff380b319f 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Fix memory leak in the ros2_control (`#2033 `_) +* Semantic components docs (`#2032 `_) +* [Doc] Fix broken link. (`#2034 `_) +* Contributors: Christoph Fröhlich, Dr. Denis, Sai Kishor Kothakota + 4.25.0 (2025-01-29) ------------------- * Handle SIGINT properly in the controller manager (`#2014 `_) diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 4e3a608e09..9b234129dc 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Fix memory leak in the ros2_control (`#2033 `_) +* Contributors: Sai Kishor Kothakota + 4.25.0 (2025-01-29) ------------------- diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index 1826e43211..7d71b64be6 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- * Define _USE_MATH_DEFINES in joint_soft_limiter.cpp to ensure that M_PI is defined (`#2001 `_) diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 17996f13a1..9689c8e67f 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index c397d04da2..14c14e87f6 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index fdc0d87ffb..450fd962c9 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index dbdf0fa4ce..4a8f39ad99 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 850f5b91b6..11c35af34d 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.25.0 (2025-01-29) ------------------- From e574645f708575070fd8ee8906d329c397889392 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Fri, 7 Feb 2025 13:01:15 +0000 Subject: [PATCH 14/26] 4.26.0 --- controller_interface/CHANGELOG.rst | 4 ++-- controller_interface/package.xml | 2 +- controller_manager/CHANGELOG.rst | 4 ++-- controller_manager/package.xml | 2 +- controller_manager_msgs/CHANGELOG.rst | 4 ++-- controller_manager_msgs/package.xml | 2 +- hardware_interface/CHANGELOG.rst | 4 ++-- hardware_interface/package.xml | 2 +- hardware_interface_testing/CHANGELOG.rst | 4 ++-- hardware_interface_testing/package.xml | 2 +- joint_limits/CHANGELOG.rst | 4 ++-- joint_limits/package.xml | 2 +- ros2_control/CHANGELOG.rst | 4 ++-- ros2_control/package.xml | 2 +- ros2_control_test_assets/CHANGELOG.rst | 4 ++-- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 4 ++-- ros2controlcli/package.xml | 2 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 4 ++-- rqt_controller_manager/package.xml | 2 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 4 ++-- transmission_interface/package.xml | 2 +- 24 files changed, 35 insertions(+), 35 deletions(-) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index d771f18d41..1433baddd1 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- * add a semantic command interface to "semantic_components" (`#1945 `_) * Contributors: Thibault Poignonec diff --git a/controller_interface/package.xml b/controller_interface/package.xml index 34144dc71d..df6784fd34 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.25.0 + 4.26.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 6c0a139cb0..ddd0d115f6 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- * Slightly increase timeout of test_spawner_unspawner (`#2037 `_) * Contributors: Christoph Fröhlich diff --git a/controller_manager/package.xml b/controller_manager/package.xml index cad0383937..f570b734b6 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.25.0 + 4.26.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index e5629e91c6..1da4d7746b 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index bce5c0de46..0596406664 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.25.0 + 4.26.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index ff380b319f..ac08e88f11 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- * Fix memory leak in the ros2_control (`#2033 `_) * Semantic components docs (`#2032 `_) * [Doc] Fix broken link. (`#2034 `_) diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index af42890d98..f890b1bfe9 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 4.25.0 + 4.26.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 9b234129dc..e3a0ad4f31 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- * Fix memory leak in the ros2_control (`#2033 `_) * Contributors: Sai Kishor Kothakota diff --git a/hardware_interface_testing/package.xml b/hardware_interface_testing/package.xml index bc1e76d309..d69f1dc34f 100644 --- a/hardware_interface_testing/package.xml +++ b/hardware_interface_testing/package.xml @@ -1,7 +1,7 @@ hardware_interface_testing - 4.25.0 + 4.26.0 ros2_control hardware interface testing Bence Magyar Denis Štogl diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index 7d71b64be6..62808add56 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 479a2b5cba..3f3e63cf7e 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 4.25.0 + 4.26.0 Package with interfaces for handling of joint limits in controllers or in hardware. The package also implements Saturation Joint Limiter for position-velocity-acceleration set and other individual interfaces. Bence Magyar diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 9689c8e67f..21d1b5796b 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/ros2_control/package.xml b/ros2_control/package.xml index 7d8344db67..b7b343d16f 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 4.25.0 + 4.26.0 Metapackage for ROS2 control related packages Bence Magyar Denis Štogl diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index 14c14e87f6..9884cf0e9b 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index 0565426847..13ceafbee2 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 4.25.0 + 4.26.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 450fd962c9..c0d0d03eac 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index 56e3501b71..583ca349d2 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 4.25.0 + 4.26.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index 568dcb4faa..3cf6fd3e14 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="4.25.0", + version="4.26.0", packages=find_packages(exclude=["test"]), data_files=[ ("share/" + package_name, ["package.xml"]), diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 4a8f39ad99..f66c8b813f 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index 2cc29f2b01..8e05d47ae8 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 4.25.0 + 4.26.0 Graphical frontend for interacting with the controller manager. Bence Magyar Denis Štogl diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index f8c6993bba..49427586bf 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -20,7 +20,7 @@ setup( name=package_name, - version="4.25.0", + version="4.26.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 11c35af34d..b714fe7f2c 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.26.0 (2025-02-07) +------------------- 4.25.0 (2025-01-29) ------------------- diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index c9a91f1a91..fc6a22a3ec 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 4.25.0 + 4.26.0 transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this. Bence Magyar Denis Štogl From 5d4933d2945b72bf2625a2a28c98107433c31d9d Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 7 Feb 2025 21:49:32 +0100 Subject: [PATCH 15/26] add tests for copy and move operations of the Handle class (#2011) --- .../include/hardware_interface/handle.hpp | 78 +++++++------ hardware_interface/test/test_handle.cpp | 103 ++++++++++++++++++ 2 files changed, 141 insertions(+), 40 deletions(-) diff --git a/hardware_interface/include/hardware_interface/handle.hpp b/hardware_interface/include/hardware_interface/handle.hpp index 1dfd499c2c..852d67b98f 100644 --- a/hardware_interface/include/hardware_interface/handle.hpp +++ b/hardware_interface/include/hardware_interface/handle.hpp @@ -15,6 +15,7 @@ #ifndef HARDWARE_INTERFACE__HANDLE_HPP_ #define HARDWARE_INTERFACE__HANDLE_HPP_ +#include #include #include #include @@ -29,7 +30,7 @@ namespace hardware_interface { -using HANDLE_DATATYPE = std::variant; +using HANDLE_DATATYPE = std::variant; /// A handle used to get and set a value on a given interface. class Handle @@ -72,55 +73,22 @@ class Handle { } - Handle(const Handle & other) noexcept - { - std::unique_lock lock(other.handle_mutex_); - std::unique_lock lock_this(handle_mutex_); - prefix_name_ = other.prefix_name_; - interface_name_ = other.interface_name_; - handle_name_ = other.handle_name_; - value_ = other.value_; - value_ptr_ = other.value_ptr_; - } - - Handle(Handle && other) noexcept - { - std::unique_lock lock(other.handle_mutex_); - std::unique_lock lock_this(handle_mutex_); - prefix_name_ = std::move(other.prefix_name_); - interface_name_ = std::move(other.interface_name_); - handle_name_ = std::move(other.handle_name_); - value_ = std::move(other.value_); - value_ptr_ = std::move(other.value_ptr_); - } + Handle(const Handle & other) noexcept { copy(other); } Handle & operator=(const Handle & other) { if (this != &other) { - std::unique_lock lock(other.handle_mutex_); - std::unique_lock lock_this(handle_mutex_); - prefix_name_ = other.prefix_name_; - interface_name_ = other.interface_name_; - handle_name_ = other.handle_name_; - value_ = other.value_; - value_ptr_ = other.value_ptr_; + copy(other); } return *this; } + Handle(Handle && other) noexcept { swap(*this, other); } + Handle & operator=(Handle && other) { - if (this != &other) - { - std::unique_lock lock(other.handle_mutex_); - std::unique_lock lock_this(handle_mutex_); - prefix_name_ = std::move(other.prefix_name_); - interface_name_ = std::move(other.interface_name_); - handle_name_ = std::move(other.handle_name_); - value_ = std::move(other.value_); - value_ptr_ = std::move(other.value_ptr_); - } + swap(*this, other); return *this; } @@ -187,11 +155,41 @@ class Handle // END } +private: + void copy(const Handle & other) noexcept + { + std::unique_lock lock(other.handle_mutex_); + std::unique_lock lock_this(handle_mutex_); + prefix_name_ = other.prefix_name_; + interface_name_ = other.interface_name_; + handle_name_ = other.handle_name_; + value_ = other.value_; + if (std::holds_alternative(value_)) + { + value_ptr_ = other.value_ptr_; + } + else + { + value_ptr_ = std::get_if(&value_); + } + } + + void swap(Handle & first, Handle & second) noexcept + { + std::unique_lock lock(first.handle_mutex_); + std::unique_lock lock_this(second.handle_mutex_); + std::swap(first.prefix_name_, second.prefix_name_); + std::swap(first.interface_name_, second.interface_name_); + std::swap(first.handle_name_, second.handle_name_); + std::swap(first.value_, second.value_); + std::swap(first.value_ptr_, second.value_ptr_); + } + protected: std::string prefix_name_; std::string interface_name_; std::string handle_name_; - HANDLE_DATATYPE value_; + HANDLE_DATATYPE value_ = std::monostate{}; // BEGIN (Handle export change): for backward compatibility // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed double * value_ptr_; diff --git a/hardware_interface/test/test_handle.cpp b/hardware_interface/test/test_handle.cpp index 7d79c032f0..201a8b69d5 100644 --- a/hardware_interface/test/test_handle.cpp +++ b/hardware_interface/test/test_handle.cpp @@ -95,3 +95,106 @@ TEST(TestHandle, interface_description_command_interface_name_getters_work) EXPECT_EQ(handle.get_interface_name(), POSITION_INTERFACE); EXPECT_EQ(handle.get_prefix_name(), JOINT_NAME_1); } + +TEST(TestHandle, copy_constructor) +{ + { + double value = 1.337; + hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value}; + hardware_interface::Handle copy(handle); + EXPECT_DOUBLE_EQ(copy.get_value(), value); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_NO_THROW(copy.set_value(0.0)); + EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value(), 0.0); + } + { + double value = 1.337; + InterfaceInfo info; + info.name = FOO_INTERFACE; + info.data_type = "double"; + InterfaceDescription itf_descr{JOINT_NAME, info}; + hardware_interface::Handle handle{itf_descr}; + EXPECT_TRUE(std::isnan(handle.get_value())); + handle.set_value(value); + hardware_interface::Handle copy(handle); + EXPECT_EQ(copy.get_name(), handle.get_name()); + EXPECT_EQ(copy.get_interface_name(), handle.get_interface_name()); + EXPECT_EQ(copy.get_prefix_name(), handle.get_prefix_name()); + EXPECT_DOUBLE_EQ(copy.get_value(), value); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_NO_THROW(copy.set_value(0.0)); + EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_NO_THROW(copy.set_value(0.52)); + EXPECT_DOUBLE_EQ(copy.get_value(), 0.52); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + } +} + +TEST(TesHandle, move_constructor) +{ + double value = 1.337; + hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value}; + hardware_interface::Handle moved{std::move(handle)}; + EXPECT_DOUBLE_EQ(moved.get_value(), value); + EXPECT_NO_THROW(moved.set_value(0.0)); + EXPECT_DOUBLE_EQ(moved.get_value(), 0.0); +} + +TEST(TestHandle, copy_assignment) +{ + { + double value_1 = 1.337; + double value_2 = 2.337; + hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value_1}; + hardware_interface::Handle copy{JOINT_NAME, "random", &value_2}; + EXPECT_DOUBLE_EQ(copy.get_value(), value_2); + EXPECT_DOUBLE_EQ(handle.get_value(), value_1); + copy = handle; + EXPECT_DOUBLE_EQ(copy.get_value(), value_1); + EXPECT_DOUBLE_EQ(handle.get_value(), value_1); + EXPECT_NO_THROW(copy.set_value(0.0)); + EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value(), 0.0); + EXPECT_DOUBLE_EQ(value_1, 0.0); + EXPECT_DOUBLE_EQ(value_2, 2.337); + } + + { + double value = 1.337; + InterfaceInfo info; + info.name = FOO_INTERFACE; + info.data_type = "double"; + InterfaceDescription itf_descr{JOINT_NAME, info}; + hardware_interface::Handle handle{itf_descr}; + EXPECT_TRUE(std::isnan(handle.get_value())); + handle.set_value(value); + hardware_interface::Handle copy = handle; + EXPECT_EQ(copy.get_name(), handle.get_name()); + EXPECT_EQ(copy.get_interface_name(), handle.get_interface_name()); + EXPECT_EQ(copy.get_prefix_name(), handle.get_prefix_name()); + EXPECT_DOUBLE_EQ(copy.get_value(), value); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_NO_THROW(copy.set_value(0.0)); + EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_NO_THROW(copy.set_value(0.52)); + EXPECT_DOUBLE_EQ(copy.get_value(), 0.52); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + } +} + +TEST(TestHandle, move_assignment) +{ + double value = 1.337; + double value_2 = 2.337; + hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value}; + hardware_interface::Handle moved{JOINT_NAME, "random", &value_2}; + EXPECT_DOUBLE_EQ(moved.get_value(), value_2); + EXPECT_DOUBLE_EQ(handle.get_value(), value); + moved = std::move(handle); + EXPECT_DOUBLE_EQ(moved.get_value(), value); + EXPECT_NO_THROW(moved.set_value(0.0)); + EXPECT_DOUBLE_EQ(moved.get_value(), 0.0); +} From c302212822acc735cdb6dd2ab67d4e967c201bcf Mon Sep 17 00:00:00 2001 From: Wiktor Bajor <69388767+Wiktor-99@users.noreply.github.com> Date: Wed, 12 Feb 2025 19:42:58 +0100 Subject: [PATCH 16/26] Add scoped lock (#2045) --- hardware_interface/include/hardware_interface/handle.hpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/hardware_interface/include/hardware_interface/handle.hpp b/hardware_interface/include/hardware_interface/handle.hpp index 852d67b98f..5c4809e2a6 100644 --- a/hardware_interface/include/hardware_interface/handle.hpp +++ b/hardware_interface/include/hardware_interface/handle.hpp @@ -158,8 +158,7 @@ class Handle private: void copy(const Handle & other) noexcept { - std::unique_lock lock(other.handle_mutex_); - std::unique_lock lock_this(handle_mutex_); + std::scoped_lock lock(other.handle_mutex_, handle_mutex_); prefix_name_ = other.prefix_name_; interface_name_ = other.interface_name_; handle_name_ = other.handle_name_; @@ -176,8 +175,7 @@ class Handle void swap(Handle & first, Handle & second) noexcept { - std::unique_lock lock(first.handle_mutex_); - std::unique_lock lock_this(second.handle_mutex_); + std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_); std::swap(first.prefix_name_, second.prefix_name_); std::swap(first.interface_name_, second.interface_name_); std::swap(first.handle_name_, second.handle_name_); From 465e5d0264dcaca71858022ec907a85cba45f811 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 12 Feb 2025 19:50:31 +0100 Subject: [PATCH 17/26] [ControllerInterface] Improve the prefix name check for the chainable controllers (#2038) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --------- Co-authored-by: Christoph Fröhlich --- .../src/chainable_controller_interface.cpp | 21 ++++++++++--------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/controller_interface/src/chainable_controller_interface.cpp b/controller_interface/src/chainable_controller_interface.cpp index 409578be9b..c03b056845 100644 --- a/controller_interface/src/chainable_controller_interface.cpp +++ b/controller_interface/src/chainable_controller_interface.cpp @@ -57,18 +57,18 @@ ChainableControllerInterface::export_state_interfaces() // check if the names of the controller state interfaces begin with the controller's name for (const auto & interface : state_interfaces) { - if (interface.get_prefix_name() != get_node()->get_name()) + if (interface.get_prefix_name().find(get_node()->get_name()) != 0) { std::string error_msg = "The prefix of the interface '" + interface.get_prefix_name() + - "' does not equal the controller's name '" + get_node()->get_name() + + "' should begin with the controller's name '" + get_node()->get_name() + "'. This is mandatory for state interfaces. No state interface will be exported. Please " "correct and recompile the controller with name '" + get_node()->get_name() + "' and try again."; throw std::runtime_error(error_msg); } auto state_interface = std::make_shared(interface); - const auto interface_name = state_interface->get_interface_name(); + const auto interface_name = state_interface->get_name(); auto [it, succ] = exported_state_interfaces_.insert({interface_name, state_interface}); // either we have name duplicate which we want to avoid under all circumstances since interfaces // need to be uniquely identify able or something else really went wrong. In any case abort and @@ -137,19 +137,20 @@ ChainableControllerInterface::export_reference_interfaces() const auto ref_interface_size = reference_interfaces.size(); for (auto & interface : reference_interfaces) { - if (interface.get_prefix_name() != get_node()->get_name()) + if (interface.get_prefix_name().find(get_node()->get_name()) != 0) { - std::string error_msg = "The name of the interface " + interface.get_name() + - " does not begin with the controller's name. This is mandatory for " - "reference interfaces. Please " - "correct and recompile the controller with name " + - get_node()->get_name() + " and try again."; + std::string error_msg = "The prefix of the interface '" + interface.get_prefix_name() + + "' should begin with the controller's name '" + + get_node()->get_name() + + "'. This is mandatory for reference interfaces. Please correct and " + "recompile the controller with name '" + + get_node()->get_name() + "' and try again."; throw std::runtime_error(error_msg); } hardware_interface::CommandInterface::SharedPtr reference_interface = std::make_shared(std::move(interface)); - const auto interface_name = reference_interface->get_interface_name(); + const auto interface_name = reference_interface->get_name(); // check the exported interface name is unique auto [it, succ] = exported_reference_interfaces_.insert({interface_name, reference_interface}); // either we have name duplicate which we want to avoid under all circumstances since interfaces From 675a7a938879f5e38be9691515223890db19ed3c Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 12 Feb 2025 20:09:47 +0100 Subject: [PATCH 18/26] [CM] Fix the controller deactivation on the control cycles returning ERROR (#1756) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Added a method to get the failed controller command interfaces from the list * prepare and perform mode switch in the read cycle on returning error on failed controllers * Add test_actuator_exclusive_interfaces to avoid locking of resources if they interface stay claimed --------- Co-authored-by: Christoph Fröhlich --- controller_manager/CMakeLists.txt | 1 + controller_manager/src/controller_manager.cpp | 84 +++++--- .../test/test_release_interfaces.cpp | 135 +++++++++++++ hardware_interface_testing/CMakeLists.txt | 3 +- .../test_actuator_exclusive_interfaces.cpp | 180 ++++++++++++++++++ .../test/test_components/test_components.xml | 6 + .../ros2_control_test_assets/descriptions.hpp | 53 ++++++ 7 files changed, 439 insertions(+), 23 deletions(-) create mode 100644 hardware_interface_testing/test/test_components/test_actuator_exclusive_interfaces.cpp diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index d5bc3751d4..ec82da7e99 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -187,6 +187,7 @@ if(BUILD_TESTING) ) target_link_libraries(test_release_interfaces controller_manager + test_controller test_controller_with_interfaces ros2_control_test_assets::ros2_control_test_assets ) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index bef2985c0b..153ce06e65 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -214,6 +214,44 @@ void get_active_controllers_using_command_interfaces_of_controller( } } +void extract_command_interfaces_for_controller( + const controller_manager::ControllerSpec & ctrl, + const hardware_interface::ResourceManager & resource_manager, + std::vector & request_interface_list) +{ + auto command_interface_config = ctrl.c->command_interface_configuration(); + std::vector command_interface_names = {}; + if (command_interface_config.type == controller_interface::interface_configuration_type::ALL) + { + command_interface_names = resource_manager.available_command_interfaces(); + } + if ( + command_interface_config.type == controller_interface::interface_configuration_type::INDIVIDUAL) + { + command_interface_names = command_interface_config.names; + } + request_interface_list.insert( + request_interface_list.end(), command_interface_names.begin(), command_interface_names.end()); +} + +void get_controller_list_command_interfaces( + const std::vector & controllers_list, + const std::vector & controllers_spec, + const hardware_interface::ResourceManager & resource_manager, + std::vector & request_interface_list) +{ + for (const auto & controller_name : controllers_list) + { + auto found_it = std::find_if( + controllers_spec.begin(), controllers_spec.end(), + std::bind(controller_name_compare, std::placeholders::_1, controller_name)); + if (found_it != controllers_spec.end()) + { + extract_command_interfaces_for_controller( + *found_it, resource_manager, request_interface_list); + } + } +} } // namespace namespace controller_manager @@ -1411,33 +1449,15 @@ controller_interface::return_type ControllerManager::switch_controller( activate_request_.erase(activate_list_it); } - const auto extract_interfaces_for_controller = - [this](const ControllerSpec ctrl, std::vector & request_interface_list) - { - auto command_interface_config = ctrl.c->command_interface_configuration(); - std::vector command_interface_names = {}; - if (command_interface_config.type == controller_interface::interface_configuration_type::ALL) - { - command_interface_names = resource_manager_->available_command_interfaces(); - } - if ( - command_interface_config.type == - controller_interface::interface_configuration_type::INDIVIDUAL) - { - command_interface_names = command_interface_config.names; - } - request_interface_list.insert( - request_interface_list.end(), command_interface_names.begin(), - command_interface_names.end()); - }; - if (in_activate_list) { - extract_interfaces_for_controller(controller, activate_command_interface_request_); + extract_command_interfaces_for_controller( + controller, *resource_manager_, activate_command_interface_request_); } if (in_deactivate_list) { - extract_interfaces_for_controller(controller, deactivate_command_interface_request_); + extract_command_interfaces_for_controller( + controller, *resource_manager_, deactivate_command_interface_request_); } // cache mapping between hardware and controllers for stopping when read/write error happens @@ -2668,6 +2688,26 @@ controller_interface::return_type ControllerManager::update( RCLCPP_ERROR( get_logger(), "Activating fallback controllers : [ %s]", controllers_string.c_str()); } + std::vector failed_controller_interfaces, fallback_controller_interfaces; + failed_controller_interfaces.reserve(500); + get_controller_list_command_interfaces( + failed_controllers_list, rt_controller_list, *resource_manager_, + failed_controller_interfaces); + get_controller_list_command_interfaces( + cumulative_fallback_controllers, rt_controller_list, *resource_manager_, + fallback_controller_interfaces); + if (!failed_controller_interfaces.empty()) + { + if (!(resource_manager_->prepare_command_mode_switch( + fallback_controller_interfaces, failed_controller_interfaces) && + resource_manager_->perform_command_mode_switch( + fallback_controller_interfaces, failed_controller_interfaces))) + { + RCLCPP_ERROR( + get_logger(), + "Error while attempting mode switch when deactivating controllers in update cycle!"); + } + } deactivate_controllers(rt_controller_list, active_controllers_using_interfaces); if (!cumulative_fallback_controllers.empty()) { diff --git a/controller_manager/test/test_release_interfaces.cpp b/controller_manager/test/test_release_interfaces.cpp index 4dedb47241..552850b5a8 100644 --- a/controller_manager/test/test_release_interfaces.cpp +++ b/controller_manager/test/test_release_interfaces.cpp @@ -20,6 +20,7 @@ #include "controller_manager/controller_manager.hpp" #include "controller_manager_test_common.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "test_controller/test_controller.hpp" #include "test_controller_with_interfaces/test_controller_with_interfaces.hpp" using ::testing::_; @@ -197,3 +198,137 @@ TEST_F(TestReleaseInterfaces, switch_controllers_same_interface) abstract_test_controller2.c->get_lifecycle_state().id()); } } + +class TestReleaseExclusiveInterfaces +: public ControllerManagerFixture +{ +public: + TestReleaseExclusiveInterfaces() + : ControllerManagerFixture( + std::string(ros2_control_test_assets::urdf_head) + + std::string(ros2_control_test_assets::hardware_resources_with_exclusive_interface) + + std::string(ros2_control_test_assets::urdf_tail)) + { + } +}; + +TEST_F(TestReleaseExclusiveInterfaces, test_exclusive_interface_deactivation_on_update_error) +{ + const std::string controller_type = test_controller::TEST_CONTROLLER_CLASS_NAME; + + // Load two controllers of different names + const std::string controller_name1 = "test_controller1"; + const std::string controller_name2 = "test_controller2"; + + auto test_controller1 = std::make_shared(); + controller_interface::InterfaceConfiguration cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint1/position"}}; + controller_interface::InterfaceConfiguration state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint1/velocity"}}; + test_controller1->set_command_interface_configuration(cmd_cfg); + test_controller1->set_state_interface_configuration(state_cfg); + cm_->add_controller(test_controller1, controller_name1, controller_type); + + auto test_controller2 = std::make_shared(); + cmd_cfg = {controller_interface::interface_configuration_type::INDIVIDUAL, {"joint2/velocity"}}; + state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint2/position", "joint2/velocity"}}; + test_controller2->set_command_interface_configuration(cmd_cfg); + test_controller2->set_state_interface_configuration(state_cfg); + cm_->add_controller(test_controller2, controller_name2, controller_type); + ASSERT_EQ(2u, cm_->get_loaded_controllers().size()); + controller_manager::ControllerSpec abstract_test_controller1 = cm_->get_loaded_controllers()[0]; + controller_manager::ControllerSpec abstract_test_controller2 = cm_->get_loaded_controllers()[1]; + + // Configure controllers + ASSERT_EQ(controller_interface::return_type::OK, cm_->configure_controller(controller_name1)); + ASSERT_EQ(controller_interface::return_type::OK, cm_->configure_controller(controller_name2)); + + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + abstract_test_controller1.c->get_lifecycle_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + abstract_test_controller2.c->get_lifecycle_state().id()); + + { // Test starting the first and second controller + RCLCPP_INFO(cm_->get_logger(), "Starting controller #1 and #2"); + std::vector start_controllers = {controller_name1, controller_name2}; + std::vector stop_controllers = {}; + auto switch_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + start_controllers, stop_controllers, STRICT, true, rclcpp::Duration(0, 0)); + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + abstract_test_controller1.c->get_lifecycle_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + abstract_test_controller2.c->get_lifecycle_state().id()); + } + + // As the external command is Nan, the controller update cycle should return an error and + // deactivate the controllers + { + test_controller1->set_external_commands_for_testing({std::numeric_limits::quiet_NaN()}); + test_controller2->set_external_commands_for_testing({std::numeric_limits::quiet_NaN()}); + ControllerManagerRunner cm_runner(this); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + abstract_test_controller1.c->get_lifecycle_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + abstract_test_controller2.c->get_lifecycle_state().id()); + } + + { // Test starting both controllers but only the second one will pass as the first one has the + // same external command + test_controller2->set_external_commands_for_testing({0.0}); + RCLCPP_INFO(cm_->get_logger(), "Starting controller #1 and #2 again"); + std::vector start_controllers = {controller_name1, controller_name2}; + std::vector stop_controllers = {}; + auto switch_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + start_controllers, stop_controllers, STRICT, true, rclcpp::Duration(0, 0)); + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + abstract_test_controller1.c->get_lifecycle_state().id()) + << "Controller 1 current state is " + << abstract_test_controller1.c->get_lifecycle_state().label(); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + abstract_test_controller2.c->get_lifecycle_state().id()); + } + + { // Test starting controller 1 and it should work as external command is valid now + test_controller1->set_external_commands_for_testing({0.0}); + RCLCPP_INFO(cm_->get_logger(), "Starting controller #1"); + std::vector start_controllers = {controller_name1}; + std::vector stop_controllers = {}; + auto switch_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + start_controllers, stop_controllers, STRICT, true, rclcpp::Duration(0, 0)); + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + abstract_test_controller1.c->get_lifecycle_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + abstract_test_controller2.c->get_lifecycle_state().id()); + } +} diff --git a/hardware_interface_testing/CMakeLists.txt b/hardware_interface_testing/CMakeLists.txt index cd8e30028a..f37238835c 100644 --- a/hardware_interface_testing/CMakeLists.txt +++ b/hardware_interface_testing/CMakeLists.txt @@ -23,7 +23,8 @@ endforeach() add_library(test_components SHARED test/test_components/test_actuator.cpp test/test_components/test_sensor.cpp -test/test_components/test_system.cpp) +test/test_components/test_system.cpp +test/test_components/test_actuator_exclusive_interfaces.cpp) ament_target_dependencies(test_components hardware_interface pluginlib ros2_control_test_assets) install(TARGETS test_components DESTINATION lib diff --git a/hardware_interface_testing/test/test_components/test_actuator_exclusive_interfaces.cpp b/hardware_interface_testing/test/test_components/test_actuator_exclusive_interfaces.cpp new file mode 100644 index 0000000000..c2c52d72db --- /dev/null +++ b/hardware_interface_testing/test/test_components/test_actuator_exclusive_interfaces.cpp @@ -0,0 +1,180 @@ +// Copyright 2024 ros2_control Development Team +// +// 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 "hardware_interface/actuator_interface.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/rclcpp.hpp" +#include "ros2_control_test_assets/test_hardware_interface_constants.hpp" + +using hardware_interface::ActuatorInterface; +using hardware_interface::CommandInterface; +using hardware_interface::return_type; +using hardware_interface::StateInterface; + +static std::pair extract_joint_and_interface( + const std::string & full_name) +{ + // Signature is: interface/joint + const auto joint_name = full_name.substr(0, full_name.find_last_of('/')); + const auto interface_name = full_name.substr(full_name.find_last_of('/') + 1); + + return {joint_name, interface_name}; +} +struct JointState +{ + double pos; + double vel; + double effort; +}; + +class TestActuatorExclusiveInterfaces : public ActuatorInterface +{ + CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override + { + if (ActuatorInterface::on_init(info) != CallbackReturn::SUCCESS) + { + return CallbackReturn::ERROR; + } + + for (const auto & j : info.joints) + { + (void)j; // Suppress unused warning + current_states_.emplace_back(JointState{}); + } + + return CallbackReturn::SUCCESS; + } + + std::vector export_state_interfaces() override + { + std::vector state_interfaces; + for (std::size_t i = 0; i < info_.joints.size(); ++i) + { + const auto & joint = info_.joints[i]; + + state_interfaces.emplace_back(hardware_interface::StateInterface( + joint.name, hardware_interface::HW_IF_POSITION, ¤t_states_.at(i).pos)); + state_interfaces.emplace_back(hardware_interface::StateInterface( + joint.name, hardware_interface::HW_IF_VELOCITY, ¤t_states_.at(i).vel)); + state_interfaces.emplace_back(hardware_interface::StateInterface( + joint.name, hardware_interface::HW_IF_EFFORT, ¤t_states_.at(i).effort)); + } + return state_interfaces; + } + + std::vector export_command_interfaces() override + { + std::vector command_interfaces; + for (std::size_t i = 0; i < info_.joints.size(); ++i) + { + const auto & joint = info_.joints[i]; + + command_interfaces.emplace_back(hardware_interface::CommandInterface( + joint.name, hardware_interface::HW_IF_POSITION, ¤t_states_.at(i).pos)); + command_interfaces.emplace_back(hardware_interface::CommandInterface( + joint.name, hardware_interface::HW_IF_VELOCITY, ¤t_states_.at(i).vel)); + command_interfaces.emplace_back(hardware_interface::CommandInterface( + joint.name, hardware_interface::HW_IF_EFFORT, ¤t_states_.at(i).effort)); + } + return command_interfaces; + } + + hardware_interface::return_type prepare_command_mode_switch( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) override + { + std::vector claimed_joint_copy = currently_claimed_joints_; + + for (const auto & interface : stop_interfaces) + { + const auto && [joint_name, interface_name] = extract_joint_and_interface(interface); + if ( + interface_name == hardware_interface::HW_IF_POSITION || + interface_name == hardware_interface::HW_IF_VELOCITY || + interface_name == hardware_interface::HW_IF_EFFORT) + { + claimed_joint_copy.erase( + std::remove(claimed_joint_copy.begin(), claimed_joint_copy.end(), joint_name), + claimed_joint_copy.end()); + } + } + + for (const auto & interface : start_interfaces) + { + const auto && [joint_name, interface_name] = extract_joint_and_interface(interface); + if ( + interface_name == hardware_interface::HW_IF_POSITION || + interface_name == hardware_interface::HW_IF_VELOCITY || + interface_name == hardware_interface::HW_IF_EFFORT) + { + if ( + std::find(claimed_joint_copy.begin(), claimed_joint_copy.end(), joint_name) != + claimed_joint_copy.end()) + { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("TestActuatorExclusiveInterfaces"), + "Joint : " << joint_name + << " is already claimed. This cannot happen as the hardware " + "interface is exclusive."); + throw std::runtime_error( + "Joint : " + joint_name + + " is already claimed. This cannot happen as the hardware interface is exclusive."); + } + } + } + return hardware_interface::return_type::OK; + } + + hardware_interface::return_type perform_command_mode_switch( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) override + { + for (const auto & interface : stop_interfaces) + { + const auto && [joint_name, interface_name] = extract_joint_and_interface(interface); + currently_claimed_joints_.erase( + std::remove(currently_claimed_joints_.begin(), currently_claimed_joints_.end(), joint_name), + currently_claimed_joints_.end()); + } + + for (const auto & interface : start_interfaces) + { + const auto && [joint_name, interface_name] = extract_joint_and_interface(interface); + + currently_claimed_joints_.push_back(joint_name); + } + + return hardware_interface::return_type::OK; + } + + return_type read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override + { + return return_type::OK; + } + + return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override + { + return return_type::OK; + } + +private: + std::vector currently_claimed_joints_; + std::vector current_states_; +}; + +#include "pluginlib/class_list_macros.hpp" // NOLINT +PLUGINLIB_EXPORT_CLASS(TestActuatorExclusiveInterfaces, hardware_interface::ActuatorInterface) diff --git a/hardware_interface_testing/test/test_components/test_components.xml b/hardware_interface_testing/test/test_components/test_components.xml index e24ee28317..b3ae421601 100644 --- a/hardware_interface_testing/test/test_components/test_components.xml +++ b/hardware_interface_testing/test/test_components/test_components.xml @@ -35,4 +35,10 @@ Test Uninitializable System + + + + Test Actuator with Exclusive Interfaces + + diff --git a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp index 1744a806bc..0be4ed369b 100644 --- a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp +++ b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp @@ -1257,6 +1257,59 @@ const auto hardware_resources_missing_command_keys = )"; +const auto hardware_resources_with_exclusive_interface = + R"( + + + test_actuator_exclusive_interfaces + + + + + + + + + + + + + test_actuator_exclusive_interfaces + + + + + + + + + + + + + test_actuator_exclusive_interfaces + + + + + + + + + + + + + test_sensor + 2 + 2 + + + + + +)"; + const auto diffbot_urdf = R"( From 254b6e85445cc4425d8400518a2cbb607ea0f9c1 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 12 Feb 2025 21:35:44 +0100 Subject: [PATCH 19/26] Integrate pal_statistics for introspection of controllers, hardware components and more (#1918) --- .../controller_interface_base.hpp | 12 +++ .../src/controller_interface_base.cpp | 28 +++++- controller_manager/src/controller_manager.cpp | 9 ++ doc/images/plotjuggler.png | Bin 0 -> 94625 bytes doc/images/plotjuggler_select_topics.png | Bin 0 -> 129374 bytes doc/images/plotjuggler_visualizing_data.png | Bin 0 -> 188273 bytes doc/index.rst | 1 + doc/introspection.rst | 81 ++++++++++++++++++ doc/release_notes.rst | 3 + hardware_interface/CMakeLists.txt | 1 + .../hardware_interface/actuator_interface.hpp | 22 ++++- .../include/hardware_interface/handle.hpp | 37 ++++++++ .../hardware_interface/introspection.hpp | 54 ++++++++++++ .../hardware_interface/sensor_interface.hpp | 22 ++++- .../hardware_interface/system_interface.hpp | 22 ++++- hardware_interface/package.xml | 5 +- hardware_interface/src/actuator.cpp | 5 ++ hardware_interface/src/resource_manager.cpp | 4 + hardware_interface/src/sensor.cpp | 5 ++ hardware_interface/src/system.cpp | 5 ++ 20 files changed, 310 insertions(+), 6 deletions(-) create mode 100644 doc/images/plotjuggler.png create mode 100644 doc/images/plotjuggler_select_topics.png create mode 100644 doc/images/plotjuggler_visualizing_data.png create mode 100644 doc/introspection.rst create mode 100644 hardware_interface/include/hardware_interface/introspection.hpp diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index a548cd5856..0f76713eae 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -23,6 +23,7 @@ #include "realtime_tools/async_function_handler.hpp" #include "hardware_interface/handle.hpp" +#include "hardware_interface/introspection.hpp" #include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/loaned_state_interface.hpp" @@ -305,6 +306,14 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy */ void wait_for_trigger_update_to_finish(); + std::string get_name() const; + + /// Enable or disable introspection of the controller. + /** + * \param[in] enable Enable introspection if true, disable otherwise. + */ + void enable_introspection(bool enable); + protected: std::vector command_interfaces_; std::vector state_interfaces_; @@ -316,6 +325,9 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy bool is_async_ = false; std::string urdf_ = ""; ControllerUpdateStats trigger_stats_; + +protected: + pal_statistics::RegistrationsRAII stats_registrations_; }; using ControllerInterfaceBaseSharedPtr = std::shared_ptr; diff --git a/controller_interface/src/controller_interface_base.cpp b/controller_interface/src/controller_interface_base.cpp index b8dd9f770d..a86339bed2 100644 --- a/controller_interface/src/controller_interface_base.cpp +++ b/controller_interface/src/controller_interface_base.cpp @@ -18,6 +18,7 @@ #include #include +#include "hardware_interface/introspection.hpp" #include "lifecycle_msgs/msg/state.hpp" namespace controller_interface @@ -82,6 +83,9 @@ return_type ControllerInterfaceBase::init( node_->register_on_cleanup( [this](const rclcpp_lifecycle::State & previous_state) -> CallbackReturn { + // make sure introspection is disabled on controller cleanup as users may manually enable + // it in `on_configure` and `on_deactivate` - see the docs for details + enable_introspection(false); if (is_async() && async_handler_ && async_handler_->is_running()) { async_handler_->stop_thread(); @@ -92,6 +96,7 @@ return_type ControllerInterfaceBase::init( node_->register_on_activate( [this](const rclcpp_lifecycle::State & previous_state) -> CallbackReturn { + enable_introspection(true); if (is_async() && async_handler_ && async_handler_->is_running()) { // This is needed if it is disabled due to a thrown exception in the async callback thread @@ -101,7 +106,11 @@ return_type ControllerInterfaceBase::init( }); node_->register_on_deactivate( - std::bind(&ControllerInterfaceBase::on_deactivate, this, std::placeholders::_1)); + [this](const rclcpp_lifecycle::State & previous_state) -> CallbackReturn + { + enable_introspection(false); + return on_deactivate(previous_state); + }); node_->register_on_shutdown( std::bind(&ControllerInterfaceBase::on_shutdown, this, std::placeholders::_1)); @@ -158,6 +167,8 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::configure() thread_priority); async_handler_->start_thread(); } + REGISTER_ROS2_CONTROL_INTROSPECTION("total_triggers", &trigger_stats_.total_triggers); + REGISTER_ROS2_CONTROL_INTROSPECTION("failed_triggers", &trigger_stats_.failed_triggers); trigger_stats_.reset(); return get_node()->configure(); @@ -258,4 +269,19 @@ void ControllerInterfaceBase::wait_for_trigger_update_to_finish() async_handler_->wait_for_trigger_cycle_to_finish(); } } + +std::string ControllerInterfaceBase::get_name() const { return get_node()->get_name(); } + +void ControllerInterfaceBase::enable_introspection(bool enable) +{ + if (enable) + { + stats_registrations_.enableAll(); + } + else + { + stats_registrations_.disableAll(); + } +} + } // namespace controller_interface diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 153ce06e65..07af09c7ac 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -22,6 +22,7 @@ #include "controller_interface/controller_interface_base.hpp" #include "controller_manager_msgs/msg/hardware_component_state.hpp" +#include "hardware_interface/introspection.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" #include "rcl/arguments.h" @@ -331,6 +332,7 @@ ControllerManager::ControllerManager( ControllerManager::~ControllerManager() { + CLEAR_ALL_ROS2_CONTROL_INTROSPECTION_REGISTRIES(); if (preshutdown_cb_handle_) { rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context(); @@ -408,6 +410,11 @@ void ControllerManager::init_controller_manager() "Controller Manager Activity", this, &ControllerManager::controller_manager_diagnostic_callback); + INITIALIZE_ROS2_CONTROL_INTROSPECTION_REGISTRY( + this, hardware_interface::DEFAULT_INTROSPECTION_TOPIC, + hardware_interface::DEFAULT_REGISTRY_KEY); + START_ROS2_CONTROL_INTROSPECTION_PUBLISHER_THREAD(hardware_interface::DEFAULT_REGISTRY_KEY); + // Add on_shutdown callback to stop the controller manager rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context(); preshutdown_cb_handle_ = @@ -2721,6 +2728,8 @@ controller_interface::return_type ControllerManager::update( manage_switch(); } + PUBLISH_ROS2_CONTROL_INTROSPECTION_DATA_ASYNC(hardware_interface::DEFAULT_REGISTRY_KEY); + return ret; } diff --git a/doc/images/plotjuggler.png b/doc/images/plotjuggler.png new file mode 100644 index 0000000000000000000000000000000000000000..708a476cb1a39d840e047424e4e1baadba1a07c8 GIT binary patch literal 94625 zcmd3Oc_7ql8+IwF(Rysz$!S5Tgt9M5*~5^r7TLxaW#2<+vy_l!EXgv%AdG#83Xz?` zj3vrC24%}w=6j~z^S#x3-uL|ZegCLo=C?f0{k!k$zOL(@2l~1i2OwOK9Xoa$xO(N1 z!HykFvO9L{=HI&q{03gIps-_yz>cezRE)eW=Z5!HL{3nfzWC`)qJ?Z4x^mB53O%Nt zd0s#9*l|@6qZh2gS6}|Yc`p8vCd=`xr^g&+QI|yC%iE_$Q0fBpriN*_1pFEdUWl7o zaI+{FAoHfKE!DQ05|G1dEH-u=8-ZsJEAQC3`+xli<`FvlDS74{&WT_iV`KN>(vg4o zgn%CN=C>X_kA1RB%R;Z;3Ekbnuvg%}{)k!Hy;s(4M8T%CZkpL)ztOdw2ZT zL;d)JayyH_^ar1{$DIFk<|)R#vP+vnJO1bOfrDPuyPGaKH7sfO_)C8u$l@OU?%h9a9Q_Cyi2OY zB3;r}MEcS%@ptFB@?70q{+)^6X8)hWc~zh+M9Rl5*F(N8g-!IZO;Z$K*_NCP z31d}PUb&!MR$gam&(y=YyO9-P+wo!AW@S8Ka9Wyo4hKa;LmEjJ*K~2$u%ZK9>Y;Pl z8>1zN+MpOa;+3hDTg1%^zultFZlc$8%(!-AG&jcz=ZJ|@nuXa=;VrC0^XV@8r@Sdj zJ*z>AVuR}tY3Cd3WDBGmwOoh&UO2HKK3#IQJbKr$ACJ(#EIOc+Q-tv|P5-4Io=KQW}K8~pPk z?6nQM+tBfNuWXL-h~x3`*dXRIle*Q`%+Iw5CO5v>!ZUa8&8)4f}`BTg) z_WH-9f8OYwyNffF4LTjm+->3HWuns~vD;C&z*!%%es%8gZP^x=I=`^tRTT&pZlgu4 z6k8}es6#gG>t1&r4YzV0DNUeEti=zAkJhQjhP3A+@4y(B&kn3;pbeR@Dgr(Y8_z2$`UF47S8tZqRyVyIf&t+mcV4G2CCkM zR4KwBZ~C!ZS9|peAGz~o0qXY68j9swNx&ECUTy{QAyQ5dyeZZBK(%{uvba16lVa5U z@GWmCC8!n=AQxFit9t)y3Jx9;EV3SJV3l||ug+n5c{hq}i5Hh3Irq-diIX?WLpuDqbQUAHEdPw0Rdi8*Kl`Mf6%RkzIV zrAM$^$pO@AIx3-PP?6IAp4u_!GU38!Yr~goqrUp#m7>fV&gaz((t=x4ed@_qG3U3v zF2+KEv2DH;D21&)m%Q%47dmsUNxWNDojwBh5UV+d-5Z~|I7w*xHMc+7dS~h4RfsPe zzaLk7`@YURwCU^Cw-l)bY8fIb&pzNOZdt);-@e zNKWjNb?Xv(oAv7(I0a%@-T7z~f{lg@$$pDyR_9~SSAN-E6<@nr|M9Z1!^Xy{b*%lI z8O}+pyLnH*K-28ILYy$K*bEixD%)=NOAHx8+Jyw2V+}eJ^~$bHpLuVvqv|Te3z6r;vI$P9>MJH^N5pCwf=H9(U~7Cu?Gb z2vwT4;b;;sNkGDpvBuei4yh3*_n;n2r)%v|;#>|o^JzEaAfo3f@Rjj+(mhYFfp1DT zqs%gUX4gs%rBxCkE`A++4zkU)aw)2voDI^#dr%4TF8l|p8X>&YH;QRxuL)Egh1*j> zh{oj6m-<~-I}^oH9Z&p}wv@&HxPm}vFZ{8K^xm#FD~HY9?(M~;cRVF%+Q_Z2o6*PR zYJ!?8X|eC;anAxLDW#vTJjTIH<)>L4Ex4cEKk#e$a6T0?&V|~!q+K!K+u={(;uwaf zDFr@S+3H=x63@x3!}?bj;TF|x{Z*btkx()bpJqCm%vaKJsIR=qUcttMZOGA$5ALG( zVHm-_kjJAi&b+%7g)}i5xjE`z-Mz|&y@iT6fHTf{H&|e*fW1m%^gK1D>i2DHibDN^ z3DNb@nD7Z-hiwe)K@5mxIrl$i%76b_-Lv#2H@8CNBNT7>prX%LKJLwTJLSqrtAJi9kmM*z!TfH*zo-mQ(Zx7Uc@@5i)DziiR&$&^pIVytlv3e}OszOyuW6YY(&1vc@TB+06$eXZwsK<2vF#&*>5k3bAQ2X=5I_m-Ny* z;LEMK5Hq6H1Kf{U2E9vOMR=p;c zwH)%pMrSdHh55w*GwFLOotzARB>x&SdoLLZG(LPLjJ!=E4C-11XB{^xwd>F+a+%^N zg2v7lmt_XxGTB?CyHZ%1RDW64!}qh5Hvoi=XW4`egu529IeyyYWd-xqPGpIVpE?70VPAL*>Ons{)vNMB3&BjWcn)!r46 zBds%Z+`D^Ai=pGCCys@75dSnbU6Q)?Q0P}!w)ft#k7jbEU2pK%6~;L1hkfc|V~d_< zYh+cwpiPJ5?VhqA7%9A1=hW0q?q8n89l@vBa-T2c3NPjxek+Q*zjQn)&}Mk-`bMBt z2!09GA7ULliAYK z?BpbfS=;=2=3nZ-cU0GWkYP7!a7_FR(?7j)uNG*(PK!%l{&jPH#fBi+2G0p7gIJko zaQlxx{dW4`BG7Zb8Nd1e`$awtX>W-W5!(yb`^TFH==h5D1P1D1<3Ckf;YlIxMwz;^ zToC)meLT7N=8)21_i&9y!p|7;mqy@Ue~9S=TV@)-bV2DKk17U$rZlJA-$l;Pzf(45 zKJ0F{!uxUapU!=_Y=?^dfbHDhUDq$aGX3vwUehBL+YcW`9(Qvhw{l%-Qs;b>Qe1YF?$hl9) zD9|>St}4m-e{-#xywaH{F75eS%K7~v5m4LR&FjuCZa$E$lWd2Po*Q_Txv@n;)}hY7 zKO%H_VEo-9tY(}@HX@o=&Q79kvv?!%a*i%4-+%q9`2EvnW%3M%{Y3HJTOTV_sjkxuB0R1cV*W2 z<&`5Qyt2N_4qC`*?k@FW$$tpVYlp9Rb)wT3R!PY6crml86@d;Vnm>HBHlX_%t2?`d z<(%m(RSL;M->XMQW^ik56seUUj(d7si`e``2+t83_;1MDfQ0}p3A?@2+8`bNz zUmCfyADW=-!QaGrerpu|BQj%H7{QkM_9epf3ke~hmQHoWF^4L zU4~zbf8=*R$R|G#xIV#=eBRNZ`xOZXx3^FA$p)Wm4Z-sbRIR>vBwh?20$3jgY5~o` zh;oRVAML7PbH`Ajf*2Y&>dCo{g*q8V6c&anCSc7-Ad;RU4D+v_g_Fv#a4R{GKTK{_ z+qH2Sl3|RUZOJlv#O-H>y0@`#ZW)(3;{3VaAM4*9#%4!`8Hg;u@3dg`EGEzV)Kp{$ zBQwm|IUncH)!?}>LJ85uGG4U%@cbpBSESD@!cZlL_zr`^$}DfN=w1+fBO)uMgv9Hj z48^S2mVMYzj(EPK?!Iouq64A@6%AFMlv$BKh0yc+vpf)Q!Vg$T<){*$UDm|H*`A3! z8!kttk+LlDzT(>1FC=reJZ{zgM_~PuaZ{BCRP3J|Qy+pw!WA*h5DlxcOo`L zW%Eo5U3M`YEL9Ak4(KUu+2Y{+o@5V97#Tcwrw7Q}DpOZaqHJ%q#^ch0wg+*cP>-A_ zzoj-A{(evC6y|-$r;XC{7r!laD3v?*WLGYs&#m?v>Upqbp&3!&xqOB8C?e?e`IPFS zgZA>a%MY^u7IDA549;iYD>v=j{qn)EFBw}9fGMBM^g2>L8dwci$SXqwa^gCu9X(;L z^!)ZjNTW(b??9mkmV*^TbfqrOtb%-Xx$Ujebgv4o_Exeq!hA=yW6z0Xd7oks7!ou7 zj`(?gcjE$ca3k33uU;HKae_G6mQ3k0v5M3r6C=50k_ZYb{E*OzYyyr8Vv5tvX&7W+ zgbaYd8z$yJ(hVW9P~na3jfH9fW42tYfR(svj#6wSF|#rFe}~yQQ-Qg3$=-G0>6EiJ z;pnGlvNF;Q$(q#irw3LBoH?rQ5~hth(RUMmYKeaa;eSPivda-bdy9FUiz9=7CuE+t zs{Jpd_B9t&a`Cz^yHS;!d)$2fI?CT3nUAfxC|xqz_s-z|dK>+tG5bI@PrUm<_ zVP%0T@W!r{&kp}jj(AliXThBL+?am~!}ll)mX}zZN(-9w*|p=pTzK#mM%{}O&#KPW zhMMQ6mu&ax98=)i_!qcQ7Gbao+)VWgOOMs~Z)x z;iq7Cu4p^|Xt$I;KH8%0dy2R$hx2qbPP``$->Mg+Ttw#SK@ z5by0{aULwb<-;xBkf-$Nv1C5LU!L7pPpW(W>G>v7amRWn0Vgah`l4t5+4$PL#?c1@B^d8YR29KIXajQIOnIQZ41! z*Soq(r0xt89CYZ zXbST)sY=hH&0`D^hxp3`)xrmA12*#Y(iGz*tZH*DuKlSp^(yW`{Dn{Vj|blAy{Y;9 zou2sf*_t~}ot55SZi-q|mBtAhp3qqW?a2Fp8?<{Yy7!6r!7@a$PMYHI>fE4>MikE% z#;B$t38Z)3+BWwmt^Hd;KBRTpX=!N!Sn*o`BbKn8eoo!$uEi^g*`#4lIcG8RzcNWK zC^ra;x)*>jD|f+xn;8AVo)>`lCt>Ld_KFAsi%Ugv9s%{!S zY>IA_?@sd8P1g8`dnr1--z%~`qRQjdTbl=~Lq%OTly?8Cv-?p@s^kD0>#>^h`$G+q z;R&52TM7K~Q|8Jl_nDg%;#QC8IWD26=}T7@LhVQaW29)BQSyn?n)q(XXX%Fh;jtNST{rBZ_#ljG|#vVBnzFmdaIx<9269KSgFI4$@5%z%lEjvt=u*d ztLF6%g@g8|uNS>e^_>+a72nb-9v=Vn>9%d&#lO4<yl3>Bf9@$7&OM`Q=#AMB+eT zuP^jrM6^3!#s{C)+6o@Y=-1@;&(fDl4KV{nf_j7LQ&z={wNkPy0YRpsss2ydgw31T zC2kDA(&sx@rt&?y)nNMHTV zz{>!keX{sa9+!{si&YEPFRA3HR>+KaziE8T`AOtxrWC8U$Y&$#!BR&Yn@MQ&Y77w0~SF{2;GW zPO2})!fV*$eW0TEqII5OPE=o^mD0?V+vJB=qd~M`1rx`}rN&LSkp;Q%QBUvf&Gpp* zo9HZG2@fkSDJNS!`7ifSN~_P#cd$6~ReLRXu7)v3j2aBmsG+En1LP+oNF>d*BUV@? z=Y+|da=s}P!ptFNDPhj+E$hu|H0(rUY5)#41xdEYZ~Em{u~z3gU|X((;KJIze_B8+yz=CjOH`H1 zLPCEPH0a=Fz(;9c3nfyuS7E?PpGjFy`JWj?+8$%o?A_l6?bA#PE%D~9FiMW~wY3Jb zlTxny_yXlp?=RzJH{R^=vI6bE7)D=+6EqI~iz<2g8LHhkUL0``{PK=twN;|7;*1RT zh|9-GUNV5LCG-Z=Xa@6TA&5p&Xi|T~?tyRyZIz8Z+Vv|q6^1rN8_l>kk+!?5N307q?zqqb-YDn+_+NUW<@UeQHvD@?HT``^#aIT@834v4 z48icV$8@J4#~w_J9tBPUO~;7ZNlF4>{kNl4->cR*7`cnwGg8kfknDafa(JTODhOAG zAQ1s7rohm9xalkly%ZFT>m#i66xVI(^}xWDqoOXv6x)F&yppXIVIK8cP%wN%xN>=I zewdOG!FQ)=RzyCq>U-(r8tLND(qZ?@TB)CYl4IQb%nyY+zU@=6OF&;rIJ&TpVqzPAOIXbj` z0R2F<$W>@`ys%+osa-aKDbm)ROlVt9j1sww&xkSTD*%0zuBQX^>THb^oS?nBWLjdE zD6zLhvi*Y4%v5W3a38E(AgN}p(3%E|w`P)i{hp8G{ zKI|-3XPOvMz6HH@rr4+zFGI@9zN!lYon;tSOPo_2^Bd5^rRGcBshHo5s($vAnA6K&b1piV43zEso971R5BV~00NB&(1y8wwvq&_v{{k1>BdonIi6qclD*CS zO^fV^879Y>Sk5r~$!GvtDoy)v%MD>wV|O=C+N9l)-7kO_$m-GI4!jl=foCtLAqNe2tM<}N`z@!N&u z#M#lhy6S$IkkQ%|C?-oYPIJi}&?Rp3m~(_B>_xrjXX+trBF{>#ihOpbf*9+S`{4O6 zkZ}rdt%BCOt6AJH-)$=RJ?3n81xNA9RS|HQ>Bo~-^g12uCf(SAHJJEH-|G3_$Qiwl z|FeBObu;JbHTWZuXCl{L+}i>ym!qy3{F=CVMQ3T?%McyL6iAFa9umCgAkQ=b-@7Ox zx+QvgSDqM-Fa=tC^KUu&vqX5I2OG+!@$tTvoLL>52?|gv2ChQyC^^!(T7VJbNc&|y*NDUs_1=9R_p(d2G@G7*&6#*u(Ei?!m0>5H_~$v}Q5GA!)l zSHdfImjfu1;Bsf9;iS|fr>&QREP^;R9v>Y`m9VH5@m4z^%XElu4t7k!wD|4zw@-&c z+Lwn;uYRwK$^xRGnJH1-N^`Tj)QOg{p+=}$Ydy=a)@=XX1E$>0rZ14|!OLci7DIfz zB04<;xI_Flm3;Mv?AoPhg#BS4wuWi>BvvZ-{Q#Lk=tdFSk{ug0`3V zd$`gaBdzPxR{H|F1B{jN0Qq=b7|feM<{4w3;%xgAeAg!uEWEKB*&7%iudS>|l0FbR@?^?6i!0f`S4E@G<5ZXO_yNTBY(F!=K#D><_s~B{fI1vC4b&Kc_{;+FnBYuTA z=fQ4i=Yg0LF&O5c%`X}p?w7d^?@7JlRyCOfH-DEIQfB=oZ<;2hJEy7j7KA@Pf~s%D!T8_{k2r zzZ!o1o%ka{)B9UkR}Soz&D3q#`Fq1~|GF}K8GT?1UWm6lndV=t0GRlKuV;H>x|8p! z=FlM%9b&GHvWvm4Pqm|Bu^S0Q+e|ihr-Kk_whL%6wCYJ*CbS~=qk-TJm|EYXM;sDm z7u_cRL=?JeBlOvl&Up_z~^Uol%g|$>ClP@_%Vgug* zL+?!I#{nE0R6C^bS$+*P9Se1|T6jdBraI0X4+NIsi>&P!4>Zl*GAVR2uvM(Q!m}8S zyQ2da{|-7CB#%vRjz#dB_c_9Za3A&7VC;}#V0hCXE88*CQugnoV5|J%!0%~~eqZIz{mFwR>fh6nrc6ySPWF&mg<-X)+F-uNl+UmuMxHc1}WEDmew}(3EJU z?TWm4!`D6lWmJ>BKSj#qUykG|pq|BM=p*S+0A^6{Q0+-EcgTh)W4q8TDvY_?H?pT* z3iQ&}Wc4cVOqf?>OL61V4dW82rbT0nC`>^d8uqHi8|1qK$6lbsEFZh%7_j6-2SLPj_cMl1t?naI(U!#Wexshnmw*3XLkH zY(>B_MJ|~zTO%E|?{o!d!e6p0J7Ih6(*mT?P%MKj6e;r3#JjM6rILs(ADL~>Y`HG+ zxp&=&El=NSEcdd@LD>~;@_Nr`@M|E-w~y{AQ~yp13MB8fRqsS22XF`y!3F38F>E0K zM)YJOU(O_lQ!l?D?9_)pe|*$etq?gdlYGxNc0pO+~&wsCS zFRhesJSTSPCQG+5+F-Utt!itSdp9Fg|AfkcBOT(ouvlSS1fljyL+g`5>bPAh>I00A zfZE1g&Q%P$X1xZIclAeuG$t`nd|10@iBby_tqIjm2AmGMhB>+(Rt6@W zxuE+h-7g(Yhw4CDiaY%$K{lhRAEGz$!VjBq5somC*bx^R_@0hK+~RN}F(u{=2V^~J zW_of+ZXF8tpuxW#(X(lr1-GpB#5!*2hb41SH|MevEbnwwtgfVLRXWa(H0P!pZZmU; zyLV)V*el3U*jvTUMQu#q&X;KoX6|GfL0<`N2ki!_H2W@Xk^T8vZNL;h zJLtJ^%702%%0vdp&EBs@v|5v}bVaj@&rh`shTbz5)L4tU3NZ#lMp->aJo+sP@J>ZB zhE0nh?NuJ+D&=^ga^ub!J*C2b2X!6t_2b~Ji}Ij9)AV;EODcn@rR=3 zq6SdKS+~b@1O|=6Am#ui)bn;4sGM6X{Z<7HQqO!MmYip*mes$xwO?#9W#YE%L=*BQ z?b}P4#VcO3x;x=@!=fQxP*b#x@MohOu>;WbS*=;B^QEyg8KXXtL%6EG?Tmv^cg)wb zMIKm;4fHHo$-peru;UWmcLf;JB!>t%Up}L2dF0Nin_Q5KcugqI$~YY>aE$_Ev(-&H z|DN@Oh;^_2w}KeMj{CGL$k#{nJ+SSC2oR4$)ap!qgPZi-EhiigCl^f54Ui@?rJj`v(Xeo?3z022q4f`>Yi-c zbAaVG>{3TgQx6S)0@APohdkDt;diPtQK-my@Z8$Pun@&Cb?QxzkJJ5yY0S@;Z%x0> zzzO!XX{Nz*A+Lb?C#W~XEQ^a)y&C4t1t~k91|YI&;<;Pq*L^mcu-Fe&gH_E!;j2w1 z8w5~ts?X@w=QJonWJUWqm%gbd)g)(%q|RYy;qRLFV(*%kSKg4pxjWs63iu zh2;T7J}=qbF;3?ewH5&V2wLJy=0AJ5w(Ca$oij0?SD?OTI##HvTc`?cqR!?O4vp2E z8DYM#V&7)cSGygTGE&*YeZ~n74Vcf#=x8;Xm_2}Vbpg^5DrkFsUePx=I~9(5OmNGt zgKr0!bjtzIX{~pz@JDrzd9?eS+%&5N5aMty_eRd=DQ%D7{f1>KmM`m2E}ds}pKW^@ za!Kq$p-d1=-V&L*+&BaET57&&=dZ}Ws+0@H@JwVGy%-5)tQCoPZz9Z4K1|W(nn2!a3FO@}=fiSOyP|Z%z9>NGxUxN?ezxRv=L)Bd9|a~HP&;2fSZrsg*Xo$8HyLLh5n4P@{;Gq=UP*{X{BO6DQ~vDp*g znJsbnyvwE@W3h};8xd`Ia&2Nqz=`R|<#r(~kS5DS%5jR$ADfG$WNrLq1nU-dUApYe zz!X3eazA|~nz9(x{KG9%c}<{tH!8RccGNsLt2Qe)L#7y_hI6QqS#C5yR-DvLdG5US zVZZFk2~#n}?Emv^Vobb2e950E4HV2+V;l0Ib@ynqc2-5q_kJIuMSrb zSh((k2*A@?)Zihrk~~lzk?ESvudNmfFq*69VA$Dqi#V^WLUZyX_S~=jdm54g`zOt$YOkP9Use6&5eM%U;hf&cFI$T@0eFfjxdcHw z{YevglCV1bg@n9^@|g*D!-8i*S#~$z0ez%(kZRjHN zanm&;MH|r{AhJ2yiQ~knS)Estg))Xz&m`jf9&W&F-1GjyZ2W`|=fu(>=Wzu(=ogYt z6a7?j8U$$>i&wM=4(t5TbC~g^D&hX?U)a>e=GQ{RE50^}V&9{8TtgKbndWq8GLSm< zFw3$X7CB|~9323aLSLLN`4gofI0tY$Wt+_Jj3LLZwbG_w4OimgxG?viU^k9~*6v-p zIaT`#IR&$YmZ>2_nT;*d2t@yHV-c~qm_8rY7$+S=MB!bXj08f2kvgV9kMU`Se|+YW z)3715Zx&XQp{dP?27R=h!K3RaEtO=|bBxZGM^ER4F>}BG6)|+XCS%3m7K=fr&qt)F zOit}aiuRg%njRGWV#j%3q3cBnL^7m-&0YL@k-$t6TRS`ov;mmB7{X{mkDijkpzTVE z@Uz~nYZ@}hdvb>Yj8Bce&gfX^J!hh(f|*2jaN#pX3t_m~imjSkxR5p>*CtyP`<+(8 z?kb}am#Mo~H(H(^`u5kL+7%rEQIO+BHAknrx$Tg-l!wI1Q|AG5p1yG+wf0>W@|q)J zAAamQVAulyNWZ#adrLiM+`CFDct9+i_pCx36Cntd2B zPmLxLLXOh_&at1BWJdw)rpzyKw3Hr)VYTx2qY(a%J&4zMl{D zpD4XE(K0UyflAMoFym^W>C@P*X{ADIl^n(Dt`!VKf(UmPx!Y^6Qgx69sVyC1)fK*e zkO#BaE8n+jlvaMKX1UH1r3DRiI-VbMz0V&)Dz!t`%1fMthJ~M7zNn9q^)SCX6A8FW zQ+mGz9DeT)X4sG`g2^RLe7=FKkA2ma3>h;HEbq0bs@JE+aLA&?J!| zlSjAcTZYoRapz+Uc1_!Xdn@28k|ZjD+%ljAuvv?i9+ZxLy>!Gq{A;=JTf|;jwR<-u zfmSSVh?$P^%MMW|lSbVA)J8w{RPBTX86q!~o(Qg`Oz^wUa$5*pe(VZ&!=RelWJc%M zpZ3Ezxki#La8>%PPv~7#{OPVh$$}Ogybl4!)*-*7-7Ph}N!7SZVC$r^1tTsz#ot)Q ze=%OMKOdobbIV4wC=PkPqyE+Jd_r?81EdLLG%`WZ$Td@6BTdPDru$uh@y9wvTVK>> zs4n9DF6Td}gVrtQ8ESUyqGb}(bo}i(tg1mOvA0TL{k}YxxN=fSOj;Ls$SFI+!&t13SDFbcbfg?cz~mVcff8! z35%S)m)(J1)}|K9pfOg^V}anYp05?YzTXQqU|nxn)Nfd|M?nMdM5WcEfS|ov_8>mb z;C_AwaoOuVcYQm{+=_#|iR|TysjHIH@^e~l(cds~M}?W+ZnOlm_y;|~t8~7P4WT#2 zhqdXC7M3|(M#9$yjdX2$e)dhNc*sc1EVnDQ?3t?e$_L!ZSPl86z($X`D(n(tD3p=|%0bsl&(p%Zl0qV~YKd~B z--+M5%2dW)@lv2a&oAwRM$NPmA?(m=xe^X0x%z@zOtjHdfW=!>uy1k&bkj22r#tHd zEDefn-@oh-iaJk1Hf_f`B-akOP-|4v3jNoHy~O=>&=y$QXRt{y@hkPuh>tOHCf0q{ zz7j@)nXrWdv+{OaA5^2zVLy(qZ%P@KXCRnK$k29l*t)!)ODSL=m)7R;0V&~1z_n4D zqUe>!=ciKu^rbgz0haNEMZ$EA)2+Oh1@=inz&VJeTOeOUJM*F(Ec;%B=pzGK^iiRV ze)X1mGxA@JU!%`hirGOQ-83T# z;@^wYY=XumOUPfGXYRM`Of0G?lFKiT%29p!TEd_#trj0bjXe&~g zN8B-OSQragYs>L~gljVKqfNOTnz-)NtPf2Ff{qut!YTKuNqynN-3?L)+2HH>e*Yg3hFM<#Uca5LKOW3-odl+eJv%Xjb5WaYO+0q z#h=Xjc<#*f{uLggI9LLN5h7cHWtPl)K0+HrPCQvGHl4=(dWW7ubq+%xiAo>|Bf+ zkj>%eD__Kk`1dM0;YHrfeCx_M&XE$GTx+KroUBo_Fq1QGhz&PN>;OmyDPTGoKf83u8p=A(`P)|Imbu@Z$ z>4EvwC9sO+V3Y5Z-HTB>r(C3q3pPh1Xd5Y0p=QL*yTnC8K38Ohw>6TNy1`z>e zo@x7Qdu9ha-ny4GvXQu*=ky`jrApYr@1vz#%Yc0lTUmEl^gy0Y|6r6y>kt(Nlf;IvVEf{(>E_NtI1Ffo&Np<*K>a*KYUd4WQ z^e*tjdk*-veRQqqeo$a^UBe0^rw^nOOqLsgU2_Pwn~Qq+3A?XJ>tU==q8S*gAq-sw zl;7>C{NEdOZslke`~MjqFGMSO+JZ>g6IMfeVpmnPeo z{rEkbVZrNp%!6C}2`dU-JC`n049^u67E895&)*6TN__YB^7(64*K!Zw?K1lme5@We zUG?BQf?D~8a%+)iuuruQZ3lr|<&M`*JU0`_x>vSGrzvW$z(9OX-(OyU7!Ahdwt`nS zO(z02Fu=m&qH>$|3b;P{>qhgoji6J&Q8Ggm`5dkScG>I6-|sT8%*8UYo@?L4=Wf-Y z@4{_>zUYbTYvn28ZXZB7HP4`;eO`*E*@xJvCWF<`|3M&j0h3l@L}iYb6XF9Jsh4tV1~h?o@cbSpk_ zdHL=E3kypuA*2Toh#?KZY$%{iX_uiyqJRmcCxw9x^<+eFRbxkR&9QW4x7l8_3#ttm zkVmmkc$}SyrSEUr*kFy&2H7};rpKH%VGy=rAexz~s;U+Z3k6zW+vo}ix0KVf4I19z z0Jw##;a)r;?Ta-7Tz`KH0*CK(qCL6*B>aTALl=ILwd>ha|&^#0_>yuZV~?}AeEDuW;sicQ4G6?%SKjbAZO)lek^ z<6`MYky?WTFH3g%BG4^$V0t=O2$a*X*5AkEK@X6s$RK4UZA_cXu6m6I*jrS49$;Pq zGDKPVh;OS16!Xj|5xp7;AnD`0(<_H$p^nRMS@fQZC`%pWxnNBuVBMB_d|lCCp^IGh zaSMTfW}gO%CuIarqOL705bLw0z?{JxVZx}D*ci!8Vly!xlTK6cD+>U#0*QoL0<)~g zd_x#B>0^DU8ug}L5lOp~Q~Q*S<;m#}M@^#sb{Iw37y?F6L06wLo;A*AfriE*CG}R#LIDMFUwp&viK* zqX<<;#~6}t&jvlhOP5o-TR~dL2SOSF7`ylPFCUWiIEOpmpWrZGv($dSU8j@th*g!B zap(J=#J`{M&77EPBd2|Z>Lrh)1Gm84(P=*M>bY}k^-EzKmfl0_Mo%P>Bl5{-Zm42Z z>_6&mZ``}H6O90q%jiRWbg_v(cT@aOHw=4RE4~!m-Y9QWy5t`|t8^&!l=)QeTwh*- znUx{g(#ad{f}zqz{1!aOuGEMW>gWtmWR9D)E=BMM7QK%>Sxu{R1SXzvNv1t0MhI&W zNDvi1>gT{$adg>O{cX}Y+)QCWkjfMaTAiKxd9HPGUhhKdyMdXSGT#*^InTN0@SS<_ z8<*~6GK99jeS0b5E0|27)Av&tJ)E6A$QVORix};IxmQg?5wpOI+gu_6 z3bt#_T@hL6AbNF-J|t4tpI{9PS93-ylfY#)6O-060{49A*X}H>>WfYabmLGGA=+>e z4bJ#LeuM5nZDQWfuQ+6!fBgopoToeaPxz@`9;Lt;)MU3$^^&9n^pA);@AD*PpNR?a1o_xq&{=6RWDb^%%?~I(;9@3xPP`KPO7s!{S7sbF~}uTEr2h zxn7!#dC=C1aCi#cCJC}+l|*jt78au_=?n1l6oZGzDZ^~-UR{k&PAScUzYMqjwGUwO zUtd5iq`lH@N>&7_K%ZvuoUfdM0ckKFkmpzLIjQBY$o7rvVfS_bKM@dQIo#<2n5F+0 zby8hW9lCBFw4@6#j%-{<#qCe#w{jVJT`vR0Ix3^c5aGnuuqQml7X?tG<9BT?gn5os z-T}_C&t$lewvY?d^=@4!v29?@tM-t^XD9`My6gGofJ}v}A_gdM^0gI+8)XTGf$3QnhTx3D?Zer7Hnch zqRagAAh(daGBq&OKqh+eUYbsM-q{KDblRE(3iJS|RUa*lZqcz~V(AU*PBe#j#YYA> zSm3BBfZM*5$Ncg&JO5tP;Qg!u)5~M+Kvw1p+PqD|gTe1!%+c;7SNgagePjWc(iW&aNvhY7tRhCuT++_ZKQV%Dw%8Q=%<#8$ zTv=cj_^Kw!!~L{QFyyhj%@MpS*!)jm#C+s(BH=rE@f(#6US0!V#`IX$v4siT&7Tgs zbW6%-`mBJtyJRKn-{g z@5c$@NdRwALV_H1OaCCi{d+&F(ihO%u=3Bp z|H%C$<*Ly3=VE60Z#nHRA&&V_l;r|9+M?n_;`+st$=^AQy=vgF`%g>%2chxfF62+f z%%>X~K;)M6p2tje9>aeO^%}X_%qe{Ad%5ya2A@7OWGjB;=Y9C=ri0A|is+dF7&R5Z zQxqQ)6En_6_p_}6*LD@+A-fn?Twc_v>BlYmFYNtS-}@5y=iZ0@ml>yvD(Rphkghl3 z8LaYv1CP$sX{%cQ_t|&^NxFK4U`7Gre973Gi0V-d8(?izdt&p0+KSl;T(F#XfBlk_ zf9E5CSq7$qJVkQz6>k*RKeN!C=Le3S5kMCM1`I_gLzpEi1=V^ij0}Uy#e!P`&c4W} zyMD+;hb_PsO#9wB|Mxr4d?6U%)j?G41UEPoobH8Mp^*B)2&+AXR9;T+I%K`(=V1Mf z@7}2+{@~;T6D>7^^tokVpgkn}1sIiJ08(J#{RPIrV4rL8C)1C)VS$qn5U6jf8&iHK z%zr@bY6d#x)0Ygq1f?#+RfC0f+fF6+9iBUgY zX@Q`3=**2sX=qzaH{3`0_T^J(c*+Qhz?gRr${c^$Z<*ZR5yf-yCK$msdKh8+LLM;r zbbOQce9CQbF~6G3eUEB~LQjr-9T=D(O&! zhl2WG=2CgQZOOJjeJO-lyl5)buU)+I^B*!nE5hQS-GCNaDx5BVOnja$nQ41b9K>x5 zn1(;8_g4h}#-@J$b7xoz-fzv5G1A1sBM#KFmhH_YJ?;yx>2NFV{0(?Te^MrJ3Ith# z8Q3znDcw9Ub%+O}1&)?MpsS;go7}s1@BGwD_3L@iJUeFg(?!L%TEqQl=WcD}AC$#; z=J9O~3=C*jTI$kMuPp}%$hkWwpELbVB>l)?yIJ&8m%e?9CgonsG!M*)Ds-|T<(o>H z0Z$4ULj)!c>xg~i6&_x95gzCM0#qcYWFxK`b!>NCY_285z&AHeLCgTdK)m%1&_HLZPRlUN&Qu6{l6Sq$Bl zMvge6+ z$(13u4jt(xV6>|s(@ml17e-h&yuP$~0+?Z`U^4Ef&jJk8(YBENa38>DtTr%9RJhSm zBRyN42#fPgpFmUCZd!s_fK~7<4QBNrjBU(8fK0#U2gHWqZE*e)0LU+lf(vUMmKZi% z_r->LD5VB%`)q&(M*whSTwq>qmW3b`5^_h=Y`jtaSvB zo)b2g#IQGUO ziXHnTGqfE5sR6nVdz~C9GvXlS)a!a9sgceMZmXo1egivD4m`e<*7_6#BOcx_&hZR= zvPiXQ6cmZDC?GfLN=~O-xc!287#N-=T$&Ha41L`GavRKUSEU;wyy$ZcJwxZ+hX8B% z9`~J*Kuom6{U6T0JP^vg4f`YtDY7J$XptyMLde=82{DH36_S15NwiYpC=|w0F=lL8 z#=b;FDB1TlVeGP&^}By`-uEn=_xrwo&N-c#o_U_`u;_En+^TQalXwp;j<z1!IW!b!1goSS@Nvq_r7>Yn> z6Ugc=guaqJ`_s9IK*xM5w)7lSZoh$gtV{_QxFHQkrk>?izKT+%hr2aP$}VXaqza>z zV(ACr$O6_1dzt5o7fAmH`XLR7}!eXJ12LSHJpkzo1?2p*8fjo!X7BNkLq@D{UvvvXS z6UgQXXh@6hdX7%6mSeKQGyV$F-Lvh3-41@K&~3gpVhhg zLcJ;*4^ zriT+C#fZtZv^qQr793C^&%6iNFt=P4Cm6H+Vin<{63L}rXsD&bb%?LA_)ttVu@?0G z*>!CSpXz1RuSL$#11syLpiYQ2oLrxI)fD+I&+v*Z#tYs7!d=ZYI5ya_jev5IxlJVsTi2KdqVk;ZNJRBIu@J3yFQI@Z-=RgH21_n!F@g6da!6<(sr5#c zU&DUy2O7y`HI^r)9@>SsJTf=E-XVn*Z%pSEBRLag6)fUO$A##z&avuz*@k6|kU#~Q z>BdK?MECo$9BEsqQx%3<(`5}a72n*^b$Hf%XzIKC0o_297n^RGZn#4ye2&TufW>Se(%yoM3~+9}!cEU587yb=#{R9tM!|grIr`c+JWyH%c(mQg8V|f+8|MRv3rcSaUHa%n(^a!l%N*V z=WV6?$e&trkAwK8b{9eGK^kyi8z6mwm|nN)Vs`>g$QXsxHT-bBTjDeSP*AU)E^X-J z`7r^FhiC-_oI$|@+0US5t z6FSVmIeQHQ?f|Yoim8yVHAKm51Tg8rhYue#-QC@DEIC+k1J@0> z*Z$!jk&vGF|KbHVt8wO1;UE%x1ERx&wK;(24#R^hhj7Xm=QK6Z{PBc;ohkrjY+9X4 zA3G?T`N)qmc7V$Coao*)htWmhwr^#gLt(ZSx*@MU2pYO$xdXEf#&8Mwblcl1t<3D( z(l=q~qD50!*1RD zw)7zSlzsJ6Lk#?mxvRnR9c$l*;TH6{&F<%vtDl#Gb=rj58b{m8kD`gT+r+inU72&l(idO;_4 zru;!W$t?A6x(^_{@NQA$RMs{3%rwh0=%%P9L*A0h5(e4Bkn#&9}p=!}|BB z5+II1RdRvkRMikeA<32tJwubsTLSo$y3Btsx~d;?EoR z25HgB+P-3+mF2k~p{#8I2mXHXU*kWD=0}tp0*Nakr3zPk@hSrr-uU?VG{kH0hlyB4 z`0W%Z*7IC+a9ToXG3^%!n_KQB5l^ftM82W?DBLFUIoCR?!Vg~erfg%!DniAT4D%Nw zi&8VAl$Cv{%gaAXgJV9b8v0c2=Lw3ex$$U6?RDJIvWUbgi>*O1=JLVA3i~Y{rUvny z-S_%v(EhuZ9W_%I`#sucMVAFiK0!U_MrHV9&QhU^eb}UK(vS;Iw14^3*kpE+=TZu2 zF*T>=J%MTF2t|=r$f?55zUoayBkR0n0fxiUXB;lEnb|u^Fe+S!ZtXoz_7Z28j4@>K ziPBya4S>8wy&~%6=hP?Zw(dW0U}H@tXiuK=^6=|qbtU0V<*_Qn4|HNsUh}B7(NY)o zn49t$l)Km|rGo1>M5BF|Qca)`;)~s)wy(9tPG9zm61*I!vua!Lj~kFxfpW+fO>6rJXlVsS*2}0##JPr}w;9YW@=I@21b<#sDxIrUom*O(dSQn)*vl-=AetEg zwKOTuWwHg3orJSKj2qZ^WsIeFX0L-w-Hnq@-GqC}tt`BVPQKWvWUv`&NHLJh1$E9a z&}khx7(HPE>kUFmtqswld3W(W^*2{#<_GYRmpBet0Z_^Jfk^uqN;KK!9|7jn1T9>f zKu$yp2(m_y(OBbfE#4my;w?>N7Tatq_>v~h?|U8W2x`u3prt44KN24CWY zVgqoa0U&d)!jv_Q7?a{hs@0R~uO}E95vo8TvRc;_U_r2Mv+OKrPyb{AD(FN=&>g?N zr#XU&eVh*nEojG`L?@tjnj7;QH`tqia4Q9Q-XIYd7;xlm5q9W6zJgF8eJlbcv+LS9 zj%`^sqjMnHSExD(OqPy5zHJ;P%YC|(0Zg?#m9FT=jpK9NN9 zt?LLu9&7-gH1FTPe;9CHha&uwM!n~zC<{hFUcubpk-|Glp8X;jQ7ZM(rT!e5!0Fdl zt0vqQ0b&9m%qC9a-b$YJqVzCBsg=B*%NWB>XWsSJYX%T3ZsI#ioX^)DG`;^4O|AZs z+Q!Rps~C$aRG=FiN83!mrq5a-YscZsZ;=(oa}kRcFK{qMzW3`iK?BO^4C8 zW+316c7vZ_-7?14sYL&-8vV8YWHmXPy(`~6 zpwFfEnC`X$M2HWdNz1Y;SkuaI(ONSdNT`u8tu9Wd+o!RaNubqj`r^2iUhs29MKfVBm%&3ith zT!YeWVZd@h%2eI+ZuX$qdI!~GL7-Uuj<_)+9_sPxd?Oh%T?LHzsNL|i8$>-A#CVfd0WMH-#W8P#_J%B81@=l8qmZl zAR`&zJxWT5Bpy?EcDQ?{?Xg}p;ED1YKQ&=>Be<16=M%7b5dFcDfCx2Oz>L-+zp2&)rVD%=yVI!l-+Vl_WRp$xb*V^ZYSODEq+F1ISdCzuL|zBEIammB&P14<-0Ea?XQU=YVS0R; z!OE2Ulxp+Z;rDM80ubW4D6Ix(46iAoci5L0HvFI#yE9cLm-*jO`O|-0ph7otHITd? zy$NY&015B+=LxPPKmQm_hH*$SYel%9tj692ptz zfUYRP;-l9yH0zeDe?13hHl<^N9=mZ9xQOWp7J2;X@&0s96+FL}l3NhWs9(a<94UD|Ddb)Lt5gSS!y{pvh?O#u@~?YO-CnuTc~oMAbu zW%>i-Mh74KL5uNXI?Um~v*^4F*lXt5f9VA9-*Ecwed(8XDxIv3-e7vPW6Rd9=YM5h z0n}O1(cjMAjtYrl}+yt2@Ax&P}u+=Z{o zoZ_)xCqwtX2nkqR?48QhuaE1amqD}kqP#8LhJN?V>hDq`76E5CbIv+ImJAo%bA|nD zK*e@^d2wSpEdQ$baud56(|O~S3lt*;!RfviDr*nR?PUu2UG{pBQjtPd6XET*S`&l0 z>~74@zuhoz)1%xln;4x``gwO_rde`!i5|yz#`1v+-h#ESjoVjolo{in7Sla7|bqpw$GH|BXjkB zGTO%~M^;uwNR*yly=4Y&pD z>14Ql(c3L*`7%+vun6bW&(5WDQ|pcNEpgAKyu~**Pq*%sti%Qop}|{KQdv-~5>C>B zr9$%Na`>rh?@IH`avjG~wyAg=R(o@Mi=o@>Zsz)s14+u&AxZhm9m{EsiIJI_lYOmc zX4}o6v`3njvP{ps?>BY-O=i36Bk@@2rM!%hS@xNcK>%c9Ce#ZDw%oe31-~+B?&iX# zmL;`u=Q@V+@3{jEW$>1#Z@q7I6ywzi7q-h-oEU0|yFKyc(HxWZIlOF{R((XeBTk>h zA#842s^Rg~CSG^aWT+#z5TN|_@-|Gl-oONhSyNu(Nb7Ql_O4lA_Ga{ECI*XQZVW9% zHmF=Pa&`Mj5^4LHbA!YkeRTF7Mh6 z`T90RkQuov%j{jDGCV}MT>p9~2t%fH;3k}Aa!$Fax<@h9Q)1<5*Woyi@iIDA2BPjU za$d^KYxBw>jd>E0r$^c6yLyx@I=nx0bn-Z>k?_WBZRB@#`RBI{Sourpwk~SP7*`jI zT$xXjXe+EeKT?!^v-0FnwQ&@m?o#5s?)z6k!#<@)v@0BO23y7SM`}9uChIkV?Niqi zt3~$%6@gr7`J&EuCG@gi))TOwBixqGS&0lb5={J0UpmL_d3$AnECGROuD?Wc?Um0U zi5BB|<4*zm?qGSB0~}llP`RuBQlR;>-RMr`u!iv?V!@t436Jh!0x}5|UmPp!=rk$| zFDtk*9^{8R^?^^b^|g#{?$46_vGZ{zKCN=`4JlxeksUQTXx^MKroFrzs$aQKrRPhF z5n0arz`ksqy*cq#yH?W0DO-ic^OCc9vrCG*>(Ul}CZ$Dqbe^~u>eQy*CgwQS>#^{= zZ*SXl9GNas>d<+_tA2kdihqdganYhA!9_(O-v2v|Z&WS!p>6AgSjTr<$cU;nIBm2* z9aiYa z8C~&4Go>84e2Oh6)uV?uHY|PE(Gac8uRXs=4?6&LyiRliY3WOa11@lXC!k*QP8h*_wx<@j@&26c0yN2YL zSLQ{FR8d z#umV2M*8^*TgI!$S}MVZb$Rrd3I9o}VWP;Fa8ZLt!R{8zKD262fmM3NvT#J*tdaPl z_mNiR%xACbN)|I2Y2s4-tXW^0&`F(nw}G9%qvuwn$Bl|9(K&ZiZFZ zq2y?;b+_#8(YHpc2O}zogx?5DS?6Gsf*)Fnv)Q&9Ny#4tAoKlOoplJas`>D6#7Nmq zD-Xxu3x7BIRQ%(0q5%q?0CH5CoSK#Erc^l{luw{YYnXI+V}7Y?OLT_C$mKBMkRYGO zkJBMbea)L4E^5~TSu6${Ik3(gr}RgW&r=BF32_{|eno$jN}QPGrC`y)(pqYW}yUrgC1F#`)mZ2D7`(;;ZJUF?9_PPt z-s*vfhZ}LO6o0jHF=|^BCq;7RtW(40ImS>GWe4mIB+G$Z2jffsc-!g~86u^>fBldM z?#Te475&(zI0J^9{}!1uQQxd;PSO=WayjaDJ~WviJoXx0nMHSBNgEozHYyAJ&~a;i zBx<*$jB%AB4f{GfA}6{Iz;Z^~Ks*ZA`uphW?N}4u))6p@Qmq*lX;fQwP_l3TA6J1l zoJtcdzVe34P_giIrA<2*^cR6MqUhNewZuAOqlPGYym&vQ6-SkW>M%Ab-UX4#(v!A+ zQMFETPu9WPAECha{OTCQNJjw#ajCmq0vGwwQv;{pMCoaVT;h9qnb7OOB}#{KVejE$acc; z!etErGuO|n?^Bd9+JhLZ723CqIZt0(v3&y&wuAnz#Av6-EN*(NvvUfV=ZlS&*}Xf= zI`XpXp<9c%5HzCkN8C7sQ3AOwBtAGB)c^rBPe;ZcNMD9HkZ@c#A94BYX&3j3;+bR z06%umQMcWML#$5lqbLWvr~bL~K$vH?VW6OX{YLuwol1bnavRCA_h_5pzAZrPl{uh@ zRUA9#%2EFNfd>ecqTO*6vDhwDJ^WuUX9xJzf`TF$ciN?l-B!ViYpOp%H9~OxEs+|E#5!e4&n(FR!819?&RnPZJW!G!|h0C zVJDS0tqkc|R56CVCp*MA;!C8I6|95rO1TuZh-VAHaL+AZ6z)POdf=kTcVuE{kRJw;f_j$qwRzBpwao{1WV&0x?sd^-&pNwTymTt)&-Z~5Pggj0#2Mh6 z<~P^g0gEbBYy!#5K+wh?x`l7K5lFily)K|7c}_fv-8Tp3*>k6jwZwp|vA4tbT?H;~ z@C(B8a@&T$Z?2E`oCJ$F(6Lg%&#(r!1k!;V+6vTg2KXt+#@xok4XP1*U_QFTZa~Y= z*J@}RH3c*R(ApDaTP~_Sj-xm+4f5-QPD=EdUv!f%yxmeD` zhi1yj7;`}j}E(j_Ftk3W#U#s z9Z|k@^!T#!j~0Y~HE~U>4RL!}xUEEF2jFgZo%j3`q(OUSu`cI1?@FXn0{Nu{Ft||B zp&2|66TuGSSlxvCZzC^udRz^MI^Yo0P_|HkxUAQZg>i6?$HzU51;#BRBOs3>0ckFa z%d*E5Aa7_|)BrS#QC?YK&srgyNW@!SG2Z>bLsnzJzqwp7Zc5OldXw`&w*I+H|8oHY zWC&>~suewS#u+<*b3vdLIq5BhB0qO%NKknZA*;71PwIo{IOGR%D3c`kW+095i760j zlAtctj`c&$pOTWbZm9IAk_oV5qD8eUc@ zU$4JBs6zLcfDB$w8~dGO`}XdF$I$_pgUC(?8&{xSe6zbe?1}^+xvkaYQ>Z~@gz0qsdv}ZK<)gu4>E9kO51xq zzXs_bru5Jua^3u$g7N4^We*v-c^lJa`}`y#VZYuH)@NWmG4+8he+j8LXj~N!kiUuk z!JGN}5&WJnz#P^sHA~>YJL5$SuV^Ay{b?4QR-amZNOc(gB}OKOd*}4&q*CTMo-E9C zOt9bd$&q$KrwKuwubD_2_Csqb3YprEzB9v0xQ5O}mCNxl#UD=s0AU8U2R9Cl-{Ov| zaNNWL9A(>IIU=jWhl{7rn~u&&b~8Ue7C+-z+wodUReeKTvJ9U0@~h49#E!b1y~(%C zH1+O1gA%G!5RPaM4B#rwTg0!An@`)tNvKNjWkg{%5xb^NQkBr+d(~f^-t7LFCys7OFt`a1d%KVVY8?G?$={}Q_<_&My8!Iip$_AzjwpWLxZ<68)}eoJ z0WgX|KV2`$;DZye)EBE<1}^d5E@(UPZmCkdf1M2H2lYYiDmD*)C6745?m`f>#7e7p z#Yobr_x47~+&NaG5f_)gn;fhL%FW<%YV9@N5W;MaInv8vb zl=R?N;BrKaWt*ucm|mylXdiwJZPgZyj)>_ycT;Jo3@A?yV{@!JB{c}daW#X6r4ZAW zc}#s^^(^@rKDc2zoy>xZ=q%FsvoK_owOf{luQfatCCB{d^rvjJFRjU(Ne z+pQ^IrOzRI4CK*Z&z!9M{a8}MsfZ*n1X87_-V|ljT7iwSw5WyBU-tBI3>R( z81nfe(H&Nm_Y~3&>j>eKlJf<@=GRBZZxW96q{6u>$-cd~0!m!O_wvgMbY_z0{r6fx zdOjkr<+zt2vF>yJ;>Tn*#yv6h1U!P{y?a7tN^nz}b@{wLhWm zo6SE)-g3Z|efA`_dT3g-ubk4x4|sP!Bet}ylP{{`rG2SzbJ9PcNuGVT_N()L;SsXR ze0bvc1P~`2ku|PqB{cYRabS63;&}lY20T$=zz=>#p&b-N+w^c}?$c!(3NzC>g6O7F z(|51^pfvU=I>*5pt2Y>1FTwnh=tA6v?IjrL)U)y_G~tywG^W`E$!gSu7@g_v9}yC6 zI!$r;yauglm`3%(S-|2JxBd2Ti#Vw>mdHb*ObVSzQ`;HmMo^W%7R!4ds^+vTB#}YT zN+m#V1xtN3kK@S&D8!`-uvKp&7+KbHkf6I+wuB<7v<(P9?F9r-i3pDf4w{|Am&EaM zPs_6;w?wMVd%-S4STYAX!##=?dbL@Nartw`gYE*+jnuD&Q8eaCU&DHJ%7_))Xbj|w zeC4xND6&Y#Yxzm*hgP%7UvHiNVQUFxnh~~hp6j45*;IkR$sd*BDqW=R2|V+{4J9}7 z+yT#{F!`a99yzUon)+EPM)@6=Np!iP!Ib)$mbm$sz7)zH*Ukow(3k)uQT_GGI%$d= zVEt0YxTsp?Q%Wdk@jlCmcBZe&II&)012}tMM+XE%+_}{zF4lYkNsG@QA{`};k?y+6 zLb*dW{nR?hckwDOg_}IZ^rRL}Q7_Kz7tCRY+S!upJn^l}l15u-L^NUX36ypRW^dAn zEynhoUFRm5AeTD+;^uuH1j$&ZNORs%($&0%%Hr*c>2fyLWtDXA06%ga^nsHh6WC~9 z7|_MN-Y`=`%zX2#cct_rTZwgkPY8bRa+pd9Qkve4zAdZZ8CnSmZx|o6b&0HfIt7*+ z2YY+J{{8$~&5#)=C^l>rgRh%``YsLZJMR6q^~_3=dtocZ@4x@47#`t{}B&~>hL5nan^v~580Xh)Wf!C^Lm9V?H)z;YOrJE-tH(f4_`{egpIx*VS9 zGwWQ%5MAYtxw-wX&L?VsX1y@QKY8-Yi~P?>7hFR61b{4um`-N?a?sxgIq|~ZRS<6r-s8UAy86=$VQ6T!tUV6WoR+8(^^0>!84ZXEgA%Ro zI)FtKBLEiJpe2FW=s9pPc;Ys(kt>;@4`@rKl@(wWbW<_eE2LBDXTObcLkHIdp4Aci zC+26fh4LgBY1mkRg3S1Dkn692 zFm!>r3n@@J2PkE^$aQ8T(9udUIUl(HxiRuj`xsC1iqRixXYx6+&Rn^GE-ji*5F&>| z|ItKfiQ<<7EcF>MQu)F2)&xzb8k)PZRfK>^5L620j}j3h0MHnI8gUvifU-vU*SR(W zV%*-Uw35A3iIOE~nw95-Br?EM`n))gSogp)A2R^%M#@pm)E~`h6_K&NFHyHjMUnPz z+gesR0)fQJ+X{9vlnfUVqz_Z#fM{jsCK@T_*Hwy+82(njeF%U8P8IbX*6+5C)_}%06Ubet7l|Qa8$rxRH5j}?GQ99i+H|WJLgGQhOaeY# zspt|)i-~H4>i{nu_g3<*JiC};ePT`U;2MC@1O4Cd;4NN%26_lvN8f;q|0r<&Sp9wg z2`(MLtEziA$d&9Aj?|z%`PmLMF%fP#j>!Kd|6P*?-RWheu)^qx~@uPk=Cn+pIaY*C<{Hfkg-8o}>fIhReCE4a`_t0L$pz zQyZgT3@gA!VS+cSPVaR=I(XcGC^t>Vh>#ThGh_@%os2?q1#MyQ9yw1@eRY!>fNn)# zOE&tlau%RGJ?HLw%xnRAX;TGXl@E{)lBfDz-ifYrjzDiPNiuT5LJm^FM>LM1?#g^1 zU4o>mw~vQG20x>OiDOlQe=nbQn@NzE{3K{2*@?PQDMU)xUp~cbj}p<(VdkWM z{H;cy^*N6XWXk~;7GYEk&=PDm9_W!x$h>fA$f{PyY)l+V2CtPi=!09VjnUiN8#*=& z3SH6 zDuL)gXw7Vq_M9IPneCndLAn(%S!PGi5XKd~Ou&rL0+O|vsx$P>;9zb6D5#~6I@Pu5 zp+=`hrJD+TEI4HL9~1;j>9O5IAgS8P7#SKGdLL#sEmy72ia=)kka_go0Obxa&_p$` zt{+%5vd-N25@CTNbPu4*9^=Fc;b$1JZxfLsH*{uOeL=LS?YHCiNB}^m%iP)2jP$Kq zgEJ`7Zk#?l>Qdi_ch!0H z-|D;L`d(3*IT-+S2aDR>0BPVoNJ%E3Pp?5dSqFfuc-gw|w1vz!34zKAQAD1zwUYj{ z7g@ZC_gZU6W$gBdYL0m2$O)+1)LjPO_YK(7nb0EJ4N}RAN3wusN9a8)REiwP&=$^T zl6SR;f;Eu$Tf_GU+t_V~j+_0|5#lowHK{oWNC%te7!)SUDcxy6E?nND-&VznUC@;j5%5s{m`y8eAj~Vq zwEttuI#XJg^X4jzb5W!p&~PIE^tCwe3OECEm*!IK6Dw;U^q^*Q{fEiG(|v`ERK;(2 zS2ivG#)zr@2{Bv?${mR(ScK1?J=+ARs4kZYr*|djU|X?f$cje0h%i_S1Ja6sWTdv< zB6b9f0IttZeoqB@o)^nQe(=H_O4h{|5EroZ$&GF!f(x)AQDq#E)Pq8YT-?qFD%As# zyN%b*``>y}c^@J_mfS~sfTUy68aEh(HUI;Ei5+HOo|TE+ngt!@Gzf$Y<1c$zlL$mP z4tI`I)^E>4^Q3(DEO5THR{MZJ)vxZA^En~LpB~*D(86M%pIZ?auG*?cPw{28U2ky{ zWRU4c997~OaD{NM9)ZsBeZjoPP;(BkA%NqF@^I1z%u#*aB4+T!8rZO?PjfSPRq(;4 zR<`YJ4Qc6jrhg$9pvgxkCh-&lJYrTI6xSkXRaOw|;fh)`>VAwdQY8&1&Um?Zd2JpB z*Bfh=`?O-DgAu`^fB`KdfI7Q((U+O$>+B>aX}Fp&7z={21~{=8`%!Zov-#PvOvv{R zeLR>UA;ywq`b7!bRIWc6_eNErl4v5@3|a8ok!r$@&KlBSBU18d5w95dB=V5aM$yy$ z=%mb@o~sZ<2zWsh(BiLA(P-J4@i`TgoWqNU$W#8|QMFPcmFtA2%e0i>q1>wk7&BRx zh$QdnM+YD|MpeC7E-Y##50JObvRg-^x;eyHgju^q$$ny?uTfBgMGESH^7 z2I?}7wJ)I)(@4}Z+NA-e((ZfdH-opMHT8Q|`@tf8!J}qJM^)76>pL7pI^9fPn!23i5YsyQ0lw2&o z;dStj`V&R80Uj2#Vue6pcgmXiR`;NR*roQHE~pV^-Kd@bfOVUA`6X(-Xx&{*NrelI zzxM8awq3e0zT}mMI9MJH%?toEx(E36@q2Yamy-Oh`xF$K8NGgZE9Hxjg^>O;m|J=8 zY)d^zgl2a=WrSrb<>0Nf+;-}Z>N!L?e+KiHjxaFG7@LMaz6vl;+t7O-Cf%Ew(C#Pl zA&Vq(G^Q%2-G%@|>5DY*l4I2hk2&cpR}uKHL!A2_KWZ}IFk<7LJ^S>MivGv4J<~lV z4_?kBN-|>|JhNlRH7Zi^vFEE^gx+{muqJze!F?sJmOs83*Ydy~Y%x)Mn0Y#xsOw=O zW(9pWg9QxEqy2xLA9Yi{K;u=n%RWNXuA~pjBrSp`lVZzfA3mhk_+6>WsP@%@jy5E#Tf$uw!KAY4=44p}>d+;@)lv&AiOw=<>@@8XTA`}N4 z8tYUG=aRiIdBi2n$0Hzq@h~+wc_q&0-vYqa0(sVzu7->Z5HjNXNm!N%*Y?@G4p+Kq zt%OD=Y>V4W*dd5wF8LG+jIO{1e^17w4^yLr@|ZWJzSAVl0jlH zH+s7{g$I-V-ac;yM3BC@k`5L^IyhyQ6^{6^2jivVpw<|*-Ja2YZsK$|DpmevHLU(I z3)mO6UyP}MoNc}G_kMsp()XDnKD)cIH0#65Q`$M*yZ8Y^XLoLues z{pSU?ddYD)&L|n<);RiWNCp9AnMpi9p)VZ#ADW^0#t1@Sggjzjp@nA3c)?*T3#`0WmBF^jZJ2OI)YDTwP|j4&5I3sYnC-OOYjmT1DP{DjTxq zyOidP14!VGsTi4Vb(SrIc<S1R+o}vfngPDLsrz*m*V+?+n%C>>W}L#y`>*~)5sGrJi(>Zr_A6T5!x`_hawN9S#0b0^?z_sH2OgIB(^ zXC0>YzJm^HhDX`=VmrdDxYc^ACkAcD6gU=He#Z6mDQv)@vnC<>rK)lVD zFz<}L2m3+?`xuSb=56dIzt=~mhBv3R_C;nk-7b1Jl3YliW%pGpXC^5yQ#<~~R=!RL zmtonu<<=Ctko=~CcwC`%5wratnl2zL7Fxi*lxh!FD&hoHf=kl8($dbd3k7t9KO`N$1TtHT%>p9lXkb} zL7~oE(T}e6SYfllgRG}a2U@edSF{1ig_^yiq~+v7{?Id6`(ysD=BjG?bxApc7sCWc zJmOW735)DlA5oV!@tLC1$d){+NBRBJKr+W#-kKQb{}boi-^skOd_u>~Lan#oEy)+- z#q;YJ^F&}{P|xYLcPMIBuY>er^c<4rNTF~q9H{->4%0&9gw83d)@-xP*}Uvpe3O|+ zNBUSplD{DNs7_pzghpoYVy7b8_Vkk4@XAB_sHTunkcif{x4iF(c(i1Y2u*J6nKC3=Vys#l6|@Ppwq2 zu5YgjF{a(|acu7k0ka4v(b*qw{+%g@p6JzBH5+>_QbjC^krL$NL-Gno>+_##4+_og z#j)p}!`de)I-kS$zieSmhj}&fxlx~_2fXLyNrf4#bc23&@{{;sdh>9x12yJ4uT`Ex?gm`RR4s77d* z>Gz6VCoWtHIhM#S>IymHB&?wHdso`qf1TN}9@^;)_Q_KRB;U6bjCOJ+NyKFi~Hy9X*}gT9;M%JyN=k3GvKuhciyi(pes^Z zbu$j+xEaWQ92^3UN|X1&Wc8B{jRGdlLwuzn)L#>IR~fBj_M; zLKZDkjK71%MiV$_!+@*IN;ZHYHNr@@f~J{Y##^bd>C`&)_9gH?D#L784K_HLFAM_C z{sNHb*9f!`pMy$!GpSL}3<}l-XTL#exnukGYk)zgLc-sI+GW&`5J$6guiK}8{~e&w z{y{;`qmXB}htAyX;Qzh_kyZ1lX$3$YYXRtqZa?EABLEuh1qr{&wTB z;VC>|Vg9?;gXHDjjzuxa{@OS%xOxHFKWG0Gbkx9M_ERn$w{Y1;jst!K2`I`uxb#6pf0X|Oe zds@8`Gu#b;hoDwGbY>ml{B1~iH-$gjvKn+V?1W?G?I~N9HD3q=HS!>;3fDNlVuk}; z0eBlSKhlwH0&Za!d*stsn0Z4YKrNY8uNPu>i$01FSS>W6wIP)4Fs zHx#w%XqgWOq~7^93QiEV6i^{^WO?@eUU-DpkzsRa`>F_DWLA%m6deq8hQa^$1lArk zhXQ|>_UTw9+~BRG!X;P40B;un2H1uFdAl3v#bEb0)%TbVGWhgd;8i=6WmooBuMP%Ci$=^qAuP#?9NVz=|EoXthj(!PElWZUptX z0EgWyGjh{ztGwzK;GlrvQI_GZLU74|RtZZ+c&HYQkr3FOJka={7a-USI2Uq!ad%I8 z{LoF*5_0mD3~zkULVtSvHZrZiQvYlPF7GucK-uHtmFH%mtAjbbPXF0JNY#Ysi8o!x zi#GS=E@Ap9ZAl+4%RNV^+y3TwyD_2 z`$`EP=RUr8P4i_s?#nOsT7frxv z*3U};_`L;EGDsljqyuu>ko^O&0)w|rwN(fbpduuK-R~MIn+=r=w=?G#mwb;TU6|>= z%}v(HcO`8(h}}K~jQ5->;R4#SEV1~jn4mL=cgGH9Yj6%5!CCKc3mOCZ*@eT~@;Im9 z8#M{AfAGFDoAh(v+Q39BrdYZgycFKEuP($GA`L@`OQwi>#q2-sIHq%Rj^Yw{;u!{COajRLEruPP(Z^2V{Ak5>9sCKTY?kZXeE zLFn-rC9(9Q$C6FjgJHz%2$XeE-34lREd4xScI_{o1VGDZ7Jyoa`wwgwUCS3m!WJz} zulywk_hQCpfymtqltByHgRr;;=aPvE_g)Ev*w#Onf)>tUz)K!!PAjE)PW(#H&K%|P zn4rWVaY=li8s=UVB;f5H_0WE&_Zm1=Dxlb57?m}nt#v92dC7ag;#y*+$zXIBDvBd3 zZ?)z*aJbDjRq^Yr1)JM%!wz}e=`ju0{Cd_iQ#t8I6+31>Y!k|V05ktne(>NUeywQf`e_pvWNP38kpxafvt;T#TQ<3 zO<)EP>bsC~)j+d9W?uw_%DopL!oZ>a1WDckIU#$P-xi=|&KqZ%LT@Es zz9Q8kg<(mh1atyTUwQ6!%3*=G9H4({f??2z>;yTCV~W z6^{+30q@=`6nOW0qDs>jh!j=a&{*c>ag3YO;F%kI+VRJg6*jHBJL3E8cZ(I3G0vIL zmq+8?t0)XM0Cx2W$t6T9z7;1chYiYXvwakwdQ|oG!}+V)3I(S8)jvXE6{n_a&0XG? z0?!HKN9NbNp7$^P!QwOW7iLAJ!**! zp1|m={Qhx(q>-HH+UWy~a^m8&1t=*%wlr3w5zfV?6I-`q_kFj9&+0cOXej>#H;%8mBx-g%csRR|Wey z4zw_qthU5*`o zJ90z)`T-r=*BLr2SG=qaRV-wz=}_wy?ig~}_Apz{c#4VSX$svY@+*!E3fy}idf>}m z+>*Ne`9gmpF5NJNLPK;Qf~fANhubAVZi5^o4_52X;j}NVv+C1qcQ-;Soo~Np*hT_> z*-6W`rgTOxyotjGkAZVz4(NC@`V!GT|GeO&pv~8_vsAnEcgy@6^ZszaHyQk8Z1qd7 zn=IRShgGX$y57K=TGe9xs7>PU*O>;!rJmwbzda!L6+mZH`S>8g70EEiG!Ef zlP{iGY^_zh=8~O%M56R8y% zn0Z)NlTK^Kl2oFTGXv&!4lFNPz)A`;=uDM5*D0V4I+K~6qmb)sztpG?*AkwE^T@L7 z9ZZ(&a!%|m-s1&rdR8`24c;=Xyzh0f4j)(iZ<-aouHH(18ZwDQGY2WE%v2wXyy_!j zLfnwDo%l(#qD>^p#Rnf%2jrx#=eu7J^kdSG-6=>>K(l(b;6=c;Y$ZNxbj2>1W!sEY z?8zS>DeHf&V*Ez5Y%~k+5dWVCd@3al#bQM`;z48vA5Nkhfy24YHiniKHVRX)Wz33G zRdx#{lw-PI5I3?+5O~!%c9@OHW3N8hD=`=7f+4eY?tM}X3~K4w>Id~L1}6|lARLZR z-`osurF(CPd$7{ZeV^D^sfnPtx%LU*g=kuNtV52|n4U&;Erg3#W``g1k?T;4!k$VE zqbi`3hS#&|yLZo|)J;!CXU`NpJ7W$8SeQkPPSU4D$>$o+;|HsO1Lt}NUSIu1EpL&6 z@1Sr1cKO%hDoE0`TGCD0!%aG{HoJj;vFpJTAF~8X@UJ}a;raG)Md|t=SHBsfpSHRx z*pRszU%mbX3oTlmF@w4N6(G**4z8a$nwZGd0^|csrd;Zi>W*?PF3x?h_3hKzvyS0# z_aO#wSZ3ZJA=3{ju&j;qiW;7pW&<{AsNy(L(jU5neI#%d0d-_3cw{EiuY(wx&!q>Jsy ze$~JBj|Culx4hM-UtJoNYS7A+<3lnF#?pf1*bo=Nvxx<|AzGSl4hg7 zN_GF!91Mio!ri|>|7pMqVk5F&;@7$D1-R`pt4j7&jAk6%75>c(1gfQUwLZp8D;FyQ z4_&qeyR)lC6aRo0ID4Vgim8kc|3zpA-9NYTiq_z7=?nT}*96?hY4O#IPy>avk`uQx zXB}T$8SrstW3H9vUi~^MkUuqE&uhlo1z|zI42UTSfLH`5(Y3FGR7N4_#MdN>Y4vUC z@G?Lzxe}%{$XfykYf_+LzAi8VeEQ6y;bn2x`K? zsdYB6Q^cyHO$>DX`|BWBOm2rZ-WkB<&h5UxTlF=48#CMulzSivYldqxoz(HHl&{*# z=yF`fc>e}b_P^Zgf9_va3!G?C!-7j3d!&GV3lN0_tL-Qx+F)E|dCr$P1!&T((5}YZ zsofz2LB>=2MqwAd216)>?b##YTE{0IcR3A|^m^{t4ss`)C~p9d)IGsND+WooDFpdB zbqwL_= zn1LP{?_ED5NDHzo2xBCXda)S{=n^24MNHW%;M~x@tX}B3^wU_wh-jSxG1#b+DP;Z* zSR$=COGyV<{>3hKA$|YeF;GkcUhsd|d+(^GvhQzL5e9@2P$_~^6r~ARC`xD%y9n47 z1W`~UQWOXv(y>cZL5dKFB1LH;y;~?22oaPj;s{9S(mTBS+&J?cm^;7qUGI9!dY;FB zT*Ta*d&)k$e)it)ld`^XPC$A(>H>*6^VEXV2lWd>raLNGfLZ}Hlk;Q^?ITfZO^9}y z!ue)Ep2Fr}fYfCdyz7Ll`;5+{T!nOvOa^LTawmal>j#8iS;g3^XVvpB*ZzqvpjKjo z9v`MZIjJXDVB`!PlOen9-Cnlq8-neTU&wen1MZnTqy_bC1nHUKBcxalIi9BZmM&Y` zfIf|t<5*q;=WhgA{e8S1v@1sqHq?k1CHiKy+9SJ3FaZI~5#9%-%Q){H*?<43b}fMB zYauTZfi@MgQ2U;IAWVk}jgc&ik_>V;bf+$%qDog8;W{VO4f1=WAPKz~xu z9wDrVc~qftB&K5DDwOh6gTl!dgN*(qn4ztY7AwnlI6VtmZUE-Cb6tG&dEM^fC%pSV z`9Gz*K(HYZ0C`{RQ1StA1%ep=E z=b>^%Cf73l(;b_Q*MWW8vw@9*0zTloxKvTIF?ZYvFrA6WFbDype2lZv%l0cgn&%L5 z`QZ~Uy~9^f7h`8P%PnoF8ZlJ2AnOcWejuxrUY0zpGIWSsA}Da<%fY*gkwtZD=?|&2 z!M5n%}8%#&T)8jYFxBdH`tl#(2q%1~*kS=w` zG7&QJ5#-ltt!%nJa@QKY83XrF_S1L3dQBXD`vw3}Db)5?J~)2Q2WYHDV@oi2e%hwy z5dDc8IDp=NaaIRkR8nPS4Yc{a|5SD;t=5Z%oK$iB8ZYx6gn|^rSnNY*+;h zTl^L)W(P~%$`R{419?OT!<_L=T;h3DKQ-I5n6rw#l#>IlfA?_e=Um5RKo*uG$Z*gN z2-0O8*FN&;o*@e$Z?lKrtxe9-Pyi6VTk@%31!GHa!y$ZqCh07=T-SBRQ&H<~g*=}x zdX8)Qk3U zSZW(&ibBat=JHibb?Bkt^`HL*YI-1y_~MG*{By}~kz@ENSW5bafbZSQA2v=jco`Ao zf7s*6NtBhOFb{QQ<60htWd(KLebR)I$ZhJuWwl-?Rc7BIdfXm8wjhWd+TK_J{!O;X zddGwBKXr(5O7O?Yl0S+@ahe=H{L}#~hs>6QAo}6-C$H#;70#eicOOrLK`7UT8(2v= z>Rg-w9m9@}p$fhu6Y5U=SvDZ}fKjARv3-Cp%pAh=T|Kv(9LfItZvFGQh}A@w*S`CqY-pL$o!oU+S`k6ATKIL^~c*Y z2>AP#a*zHxI*}v&Cl&yGHRGSJHb3)ulAy-)!6K)tA6M(HL*xthQ9=c$6<1W&z2 z6*-!QxFhW&2QK*+Ot{X>RLo>1kNnYT=snN#I@?v+^@WWd^Pn{j2if0)UZ;`NvxoVS zSDg5tKZvTVS82B4QO4+hi3{OpOGKZ_FaG-@*ciOxbfx(ZQ_Tadw_!hiuvVO`Qd8B) zF>5sDqtd}1bc3XUwB_(_Ug^8=;nC|fe)M7Pun!bq6w1d%3$eG`!BoC)&f!9Hp8IGk zA1~p(Qpae;UhGd_ay!1 zZ@dHz;;S0zigMbs<&>ni(#PH!U+1@s z57NP=ep}*4Ls+uD;99akTUkQjUyJz9AD))50?T|2U+llgdx(rKz5wrk4$i?F_Y98Y zkJp*@=-qFUJ?NoLsVN)rCepuBocz6cMS>SLX5LOBLx~q>z8t*Aay;nf+Stp8+%S(7 zqPN%J5z(Eso z6^vY-nSP_-eNuR}sG@Vp?oxL}NbQNVsU8bxw##*q9G-l2XPJFj$fdFSM@ZCjXR5{dxs;5>(4|GyVKY^ysEzh5F%69gg)|Tm75;n!Zr3(^8t$HYkjJ;I|n& zToYsVjNwS;o|sHZsR_Pb5^}Jl7;KQm4Ht6l$0u8wNddK+yPxZP+Zk*kqE$GSF-Y1Z z^5c)u_pkkn^4xdUCtam!b|x+lK4I&&f?T_)$~7VD+wBjIuNQqw_E&$<)3meZ$k$EP z0tpi ziEg$U5seP|v4Xb#UZ)%8{R(eeLYt<0+RYi0Uv8BalL~*_A8fq)*5U)*sg8%{zqX-i z!`S=d?&)6(cCT>#s?SrRT+_&VR4<=8B@$EUKT|cW@WG&>{6t3|d02$fnUv~a^uevE zk3~*nrMq+vCP4!j03ld1~qwp-D7 zZ4O_-BvC&np9)!WzTJ%L^-?!>k^KYYBha9Dblh{Iv_!09`3)a}il0XRv*F%%;mez} zMjmmyJ4`#0739e$Hne($TyDQ_GjXBEuwx*gxBoNw#m-9q65Rs3!7md%CSBu~wc94e zda^&;ro7j?Qm^%GJba&RS#_pyMs+m*HidtDO*-bwkKH|qNHXf;$ zA7$s?s3mA3JUljf!a2`n@I&b%(uA7!ruLaXLX;;=+8xP~D^(13_FL0ha+Reb?aqd) z_atQXPHQqsez6Us=l4 zv2CPe#qzDgKoag#zF9W)XKcnpmo`VVdzXH!_J6>SDLxu-Xc~q|Yw-BjZI)|`C~r^Y zyEoc@yEEL|zM@uC`KXc2wGfS5dFz5Hzd;F8_DuI1q<+5&`)W6nJdL*QOM@w;&EZ_` zyzcJ(V(qF@T8iJ|O>Vg@x2hG@mWUWHEz9b9YEiYhE)*8oN6s{MxV?_MLH=GZExc;l zXJ)L>zvS^-EuYv(Cl%VcnF89h*w{X~8nbLAhcBb=j|;lYFdkhA%8MH4WbZDloup_v zomZbO3gFTvHTh~TEA`b>SNVK$YEb0KOt^CHlyUToh+~tQ##CKJZ;suHXT8B@#r#Kn zI;|(S?;Y#Ae>mLS8Q3;ahV>mE!Fi}7y-3mA!eVW)QynXw$gSf#y@Zh36ePt|txUNB zWylKctMAQ|B?~y~B}V*{>WOPX8#&V9tbz@9%nQ^MB|M%W{){~TVbxVk?etv1$w5(7 z=hIn*b0FeJ;johYUYla0yvSwIj@^x;G7>#rRI**wTdIv|Z?@8)NB!6*ck7=Moabq@ zkgQ7neqK;uEB5Rj*&nrL{`Tid;D7W7-w(N?KF{bQ;9$>LSiFC4n{Wkh46lV`8FI$V z!}+J1bVX27U$ow@8XUU83{+rhVU-rq22IZrFp|z z^dukXm2w|#4CHW!1Z_#^it`HWJ4OOXWv0r5t?Tc*zHd9I<+o$4E71G)ali-O($jbG zUY@p#$go_TSIS(HA?&^U%9(JyEs%wmAJ%krmO@Im5q!wj6!n(CIYDYMjN;Anq8U@b zUfg57s+YRuA5%o5tbtKtnETywh{z~we|by*Z{68okJ#D#F2Ec`K#-T9%ZB$HYml5c z`2kbqzjF|HU@W_t0p6-xw8d*44nVG(A6TrV(9T{M9If7|G{Rbl|bU@bBaD!QtuZrxr>M<>B0mt@&%Fl;4Mc!l2iPqX};8XqvMH-BrRYG{Um~(By zkBIy0CjDq29m2+Sty`g}ekt>lRjyF%+)px?^PSDw<1Q4`?q7R~7$=#rJ z2)Tpa_y{n|=5Z@DT`sM-%y`%bY4@?clX-wSYz6>}FTe&j7L4Tg7Q_EXeo=FBWPoE> zkVj*1-{e5#j1Lr+DZaCEt1WqT5c4K};fKRv`Ip1lS4+=+>_`^1DOzm)RUI7hRsOk9 zs`0?MNaWkx?E(I;b+y}|GK^S_k)3WrZconHpR{oVXrueXv1NF}s`9?kWvtM0a}kzo zE4=4;&TSy9$p=m~_Th8Dc_|l0*@1VeJy+Qs{$K7AdmFeR%;FO>ZUbgdU8TuoK#AM~ z4e#%=?q7#(+#M2-O+~Dk72cVo8H#UuIPf$+X^&aUWDVFmE8fn0TuKnT^wo2;GPr;b zGS^-GJ7MG%fHd*ecOS1ZXMBbdudBuw$N$^mQ@`{wx)@Ow(3_WE44V8kg9FnSu){z$aVAvy!vS#l`PtD_r9dtZjdmO@6y7Ofe<*Lb-ooaK zQ(H06Vc>6N$~8ucQ(tH)W~DoTk_EXaV8Guh6?0cl%Ikl3sF$QQVX(rf-SO0HsdPnXq-phmF zeezKwfWd|}{7pK}CGwMRK?JrlMW8C&F1yR?gK%9V3a}|gE3Ry3%GhF%jtBogW4m;# zhXWynNyQZAN{@NHxT+hGY%W2rUTr&n?uw8s;0NMe>oS_5hdw02hDzMK(@ql!sTO(q#qoF-c-8{#Ascx|vl6Pc;zF1md*zFL{NCgWADzhKusnO~BP@C+Sn{ zXXxkgkKd4u!I_goiDVvcqwKy6dbV_se^PgKpN$>PY@$H|>9`lE>_T(d4rk(h*|r+j z1ttJ95qKBDJck@02Z#CP{{Nf+2x%b@(i?YLMIma~hg^Z@q|WB!kT=I^ps=$~x|wo~ z$_-C)%LQZNd(J-ZQ-$wrcUr&3hU9|}(o$zActfUXgA#Bphs0C@^f)*u6r%0IIm2PM z={_uWt@EG?c5F_t4Fhi4)jP2xL7V-bKj!F#w?QvdpZx@rQpBH~2ECAs{nj%a>4h50 z-s9?pg0PheelJ&HqrCVAm*UCaU-)x4&rXOzBLf{8FK&!g!*mk^m0#df>N{So~Rj}Hwq*u~ap@J2Zg5Dtq0i2X_ zm4>48@rglPd_Ujf1e(miMb7HK?bKg0BA#F~6krOI@tQ(WC^BN22hj%eu5b{MmKk+t zozkBxVDG(yW+9V#1J47vZ@p*GRT`8ISG>+GBAnaxT*pULg8;?pmxCa3KutsYsv@VA zju@Ipdu=dOK&$#Fu^wWZNb50!TxY1h z@aTdyXTNv=eXRfex>BfOE%H|E$U1m+A5?}ae#tJjBD2xqctT2vaQpB*3kP8TgFFTB zUk!u3@~LGTQ(#ijz2k%E)IIw-AaE;*`pwlsO~I;}OgHmnr1?N2(dC7s#p}KW9@LZJ z(Ux*pMRs6$y9SS%4;`U4Y;BwL82fBjVbAIGht>~0P1^8QvGIMAEmB&$ufz(X6$EZQ z2}S8Q0AB9FUAt-PfLbRgqEiBiLb;2?$9QbVM|#CTZL=7J+9?eY2P=H9(JrSMF@43e z>6rM5HAjOiNrkwa%Vd9Wp%3&EFNV(c!ET4TAyg_ccBQlB{-m-~CaJ%sMI^#~W}>MX z0QLUf>k2lj0HpHRh5VtX4hq9Cw&ww^)x8~sE%$UPHMl{2yhpA15D$KANTL`Y6qBD+ z6ft%N8NL%_r5WU6c~3QiLb*=m^TpSjp^$ViLzaA2%l2)y6sZeOK+N+@;sEn5;2IQc zk|-EXPcDY4U;GwH*=NHqzFL^l8g#q_T6G`<6z^4A3gU=veQUe8D{L)FX_&(^DI5Ti#>=8rux~c7_)V zLEG5)8;@wX8~fndFsqDh^ByWr)bSEhH;rt=xkYD|ypbbMcVBS#hRXH>Hc*i}Mr>io zXe~sar zXgMk1@-2nJa(Ab5UDgMBva1a_Tgir5Od#hz)mHw&nQhiIWjg%$uWxm^o%*9<)_{GeEuifdczp0$Z-%TD*_M?hxJUad3KFOFnC;15%8h9Ku) zT~=?P%)v_1nwkCjOVk4#?IqoHzZ7RfP~xNO9c@zMX}AB#qrbT9JWtMrrv(U0tDt%7 z!t=ML%UN7i&VmQwJqHuaBxvE!TVlY;VQqYMy1K0pV+W}2Tt2*-#`B7b18ifb} zz0G@j+`$rznbF(*>U&I>wQ%A1r{qd%XkLRITsFP^0n!g#OvwG_3%sv`Z|+fme}wU9 z)Ak0-RNZjfcQVLvruI+^>Pcm9?_N!s%EAbf(N}_|kTT%Am0R^OqH=!TU7FP!7p_z5$ui4n z*giAT(yS8T7~TzlCVu*}Vp&eP6@(j$mJ95rcQQUzR|_Cu=eWPXbZB(wni;*ZGLq&} zfXC?;dMl36XuyPrytov0Y3YiO(aKtyt3cjW42n=huF+NpN{Vd{Q+L0{e`Hr-lVY}Y z<>TGv4AiLP+gg*cJ>wtJA#qqQstqCsqU%7ed-<0)f{|3^cnR)UeEWE2{rUL8Ts5_c zB?Ps#t2y)MCNf~!eNRS;Kyt{_8dX7W;#H;9`E=Jwk1&#SOHIfgG`vost zD*4!*p*|Be<45R-J7ykz-}Huv!>*m0S+r5xN=-VDG)@r!cL2`Z{ zn8UhFw?bVkE$^SuCf(O-II%EFG_vbYEWljd4JH$J6y817rZuAq#%J=N**vZOyZ+>? zYGBiAclfOk0@`&>09ilOQ;PZL_RaHzEcEUD3Nx{hZUhLOrhMd=YHAL5nY8E^3GPft z)tm27ledPGQl3hd!aM7CQgGIL3)WddAKklosfuH9FIp(!T!r`CHKDHeAWv$5zci-p z%x5_as%5;(_%NnV&)GPlyeHiA=OHZ;9AYj%UJg#M2h2>oN?z^4y==WW=qDx?jnk@_ zGA5l5(Wh~Vj4gPx5$1iPPF8t#M2iVekX-`?YDbn;(0@4MUkaTk0eoGAmqyIlJYNDr z`rhygyg_e+!&RW~V?rnzMHZsiN4|wv-NPGF0d#ufs{>}(;;6Z7Icj9RFco>)=4PJ| zD5+`r{H^2$x5?36(^|jjTt=y`Hjo}(3J#CuR#sLiFMnHJq}mp~6nR2&x83bpm+g;f zZ~r*voK;|3Z7;9DzVQ5=HAj)G2PEtO$#q$y-@MJh!(sEsHNg@#K_gzMzk3t1Z5^|6 zK~Qaiuw$r_A0Ux7AzpUO%vbplIF5`fc?r2i-*5c$CUfwPW`Z@thkZlTV}mz|LUw*1 z$l)UXqegdo+yGOSQY>)12x{OpQ?GCv?rj+PqPP(6AYuNsBR6ZEIVs=FpR6(7$ShUD*b%WdPEPJO(|QG5znu-jMYxA?r4$_S6lL z%EF}Q?_}F6BFUAzp;pdX`&$PXT}#5m@QkUiO<+FlXBs}L{0tgB`_qx*#Sd?Y3PU+v zqh}MZxz*(E_5KkKdCI1%kn6{Y{9${0ML0M|+jrLXfHK}*`bARgOv8t@2JVT$y^Mr4 zEs=Q0j%TaEy0c^+N;oH(#7Gzsp}@7e9PTv+tdcu$s@5+)78BYt``Ce$ zeq)kS0U{+ywMdZXK9DLrRZu>E!EZ%?&^80DdG~&RJl~(rUv8bX(&4jB>0qzMI3vmi zdSC2Vvb)C6A`x6<8m5pk&87J+1OMLvM0r|sQ9w;S77lsR$d**LO8E(o zx~=f6JtnLKire7#+~HAb7TifSqcDYk;!o6)QRILh%uj~ zmwz+hE1Tg;`GQK3E9px&2zY}Bn}@eGJ)3%1&2l z54I`bIV7mBz;SVnr>PqAn<}$tx8?Tieq&`}VNt&Fk}SICv$t|S%Qf(;aJgSq!6vaC zd}G&WkIEBJfD8WE3b*?t^LG1y*X5yN^WA~XIDC0nO}!#E9mjtm4W1%{z<}p^*ou6y6`c*Sx{9+RE)Z4%-<*}u79KiCWbhH< zRmU7~+;G%vSi7A@Ba?7H!d$M=9&G)FOD*R?Tq)l&VxB(&;enW^NIT-hx%TOTN9{qI zbq(4>y7v5s2N{-sj5=Y{nSG+3mEdWLR^79FB@FBN2tH_&_MiPk!0|-37(l3Fp#9i# zw5Y%XXi++Ugvy17jW#jn~Dj?Fj7PD+bK*LMFFCEDN+gP6$A+-y?zE z9xZeh+lV=ok9IKi+NdaYexI;2Ie!r82yZQ%k^17=8 znI!rh&K3wk>Kz`c5>ZgX_v{8`G_N$+2|mK{&2G%;%-(sb5)5kYSGfb-9jY`)QlMCa zbc|x>Fo0Ph8gvP+(GGBDVEZc{2hjD<~tY6H7uv(=ILojrsQ zv`NMbnoZGdnfp8e-nZyCY@5;Od;~>N)t}@t>*;-aV9dbM^9RxY-XVEDy-tII$MOzx zpny4P%39#iK2f|B_P~#)6w1-S9)zXta@Iq{qJ1J=2&Z^sr;y9$K zfiPhi|4%V!0^${D%+R*6G!>lpZ->`=+a9RijVLM_K3tV`v@fARC-C zMX+P{Jb*1qhP?sXw>ekrG$;gTfA6uuW`+oCN&sh*#OYbEOIZ)qu?92>FMX;*gVcG>D0JX6aZ2@J%W@`0q}di8!hWaX*B`9)$9QBPRiD=ebHNu<6X%`M@235-HzbkA?pEwxhlG z-WboM*x7V~NSzd+Us{jI30(ppymv1%@FJ%|aPWVjOMvS23UO5-C4?!rW^iNgp(>yS zC0Lv^+B;{8Xl=wB@V=K!zJx~CCY4A)wSn36j!6a}gzR=3fIe(d0#BJ}Y%52D?_ z;#i2Pfso7BH!v{}vpAq9+CllEk#p$$;;=J1V%N_M%+8(xx@5HPmvfkB5(jhPq$uBD zLg{|8nZHg7X%7}lvYCrTx0;U-rnbKaCk9VNvPZe15n~6`YiQ@|UiA%N)0s6;z z3sk`%6o~zR!dLbbqu9UL0`m_<>Y;5_DHz{EmjDz#+h@#uo3p4Aczwy&pS%$6T-62K zK&&sEi|_KB1sK`J>7WI53NI7Hk-Oq_V0Y&0vDXk`bl{+UZ=9H5q*)8XxJI=4kuWTx zgZK%MU|SVNf^(<@(XQOP-3AyVLR1aeBWBYH+CdUmp9U6KM~sh?@+sT}yDM{U z9J*ww*%3d_AkUQZae3}MPd{J`cFdsRMu9j(hS8D>ONiHKJ~t|u zB6;>X1OjSG?!&2iPV{QNtwe^)NcdHnX<7VXJS9CI&a5UN1&iHDCt_#jkY(jFdr0iQ zT!%GYuN7rRZNqw(Ew(Fj|4zSG!^p_rVRhmW&ZXD{U+$>HzOjM;5TDHseqr<$5#w_ zEar$;;>pF}_1T5}*z=dy=a<)KHq{|=`Q`Qb4>0$C5w8!@HOmHE3~@LQ=CRzaD$|MJ zk(e(N++Wx0F!$FS?tuJemMaT(BI|+3^vpd7xPW;`=P;64`OV1X0am2yYJ3Me*lvIM z<&iHJ45`nzY&YT9<;ZUs@6^L|0?T9mHUYm#Y&vt;m^8SS4IV_LEk>gtr?U)M;LMRk z%uhL+po!q%q^U>xVcu#YxIV#s5qQN4^Ont7)JEXYiocC8J>bYfabtRM=Dhoy5$w`u zx(N0jqA`opLJAbl@kTLw1SJZye7@U9OiS}#`lriNJ&uLmfK(|$p@*Z!_JjC)c7#N^5x{E)pMCYI`CdFtR*AqByxfpPSegGXicWYJCcy*>}xpIvU6g1V0aOvL-fr7d|yg&i#bRpQ7 z!pxm1VR7Q1M2>%qt@Mx7_#R>=(B&5CI=s8-iK@-FBJSR0Hh6CJgn9P|~kX;sJwMgH}TV%A%jf7Ex52l;6uhH9TN1L~ZKL zW1|fz3n}Tx0(fP~)d%`3a6E+|ddr#g^5zyA0A2>g5)T+T)SY><2R;B03T0i`kBU$L z7GYKPKzVHtpuz^nq4TLSf_Xx6gP}T=^?&MZ^N5o;ye!(>-r(b#T1|tePxOjMSyoRg}N^Y zIr~`nZSJOkLddq=R0L<76>`Tvsr=G8yokg+&tkCOxBh9rztMrvMT55nO^tBel_i1+ z8J~5lskLB0r&LsQV7@*NxlOf8G0y$MnH7E{C~{@B3+P~~v$;7_xH6uC!FyO$iy11+0Uv1r zmlWB-#$ysU%McPS%z3eKkmtKC_bd3;ui%F=Bq5a1MYOts-qXJhX@O&r2i7uEi)KlT zJMIv{pCO&b0F(PRB7%^s+ttARPqFD41egK&QzQG3ViEToDXT}Ern`S8Tm9YlPD}++ zb#`|S4>kznF?!U&_K*=ye8S_!0gzWsi!l@Cpw#hGTLmkSY6LK{}1xZaBZH}64IZOasv zsD~O6=bujasI7bcW|cWKv#=NIC1L@!In&BH4zp_PP9DY%X1=F7E5-4%%}!wg`5Xb7 zURFW9-uqC6A)E{;lcX)*A9*Vfyx*akTuRW7@(Z63*+%j^`b#> zl1(Cz5#A1UF&NvIsaPJnJT+8P1*x&?kB6WTtraxGF!z?v*aczB9>*q*jccu{840Uf z+OWmXp^ibRliOkom~O;+2nSPBzbvLyXiiwxJGD`&b}Y9FO#GkwHnj%1X&$7Q#E1igrD&A6lnG=&7~_4noW{77}jdQAgNBsO=Jp>dvGV=0Y)nDj>xN zdYk{aN-hy1m8}{ozu=}Q0_nx}3;%1vTu5jz>NZf2Vsw$YvNZom$)2WM90c!1w>?-~ zlnvNaLCrZY8jHh;?Kmvujs&n2KjE$W(e6^!U{zkU9!C3lEIVd4Jy6qGylBGfzu@c}VX9#_6#r6fwwEf_mDPrFcn_;I)7Eykt9j->lR{il*7jBkF zB*-ZdX3`H5H8KoKyI?z29G(wYDss?sgTsHOiNK)Wv)yI?1+zr(t~~JW&m=B5f1Rq( z!+3e5NTP}qIhvyvB3TQ9P|djjleTj_c<5{(vw+5orpSU~06lcnZZUy8bDoWp7H1^v zI?YU@MVbK&o2~J#ZWci?2?0@3s#=3FMn{OoKx(t+M(W_?U;u21nyRGxWEDC^$b~_p zO1mCb#W{Zn)Ih38_5MFoMbP>G(%Sw>tp8_dZH>ZY1yHC`m8Jo0L*~G_Tu=uNRFDMk z@+}yLpt^ZlFCvfxyuSk7xNF(sAi+GX1$oI1&OH0v(QxN-J*Wd3wp&OIxe;7A3a9ja zAYJHXyAdN@R*ZBxrVa_=k*+b2?uftvO*F1F1+f`}9KA$sY+|#SCqZ1C(KRne2g~kr z1i{8eX`EWP&lzWd<%@aADy1I`m<;L@cFjIfiv4g#Tq|JCkH5k>q^5}hhC?zY!$y($L zl8Pux42jyVTBg9BwXHAwB!Zu&ZSCn%J$3D za0H?_9jRfZ%qNj@!bxcO+-ihhwSbipZF%JWpIM18s8dfQbJ}x=4=iWeqqIQGZibv; zbpDm(v-~*O5OmPNNbG&a*geSs0)s83MI>YT*&JDe&IWS8nI^s`+(jUjVm(u)hA`(@ zq+6_AQpdc-NS6eq$lBi)&y|5Fsf*^oq$5OQpgq3qX~X;#b4CRu14B;t;L|_ThGA5> zJtl|$rE&r2R`!7yZ$OR}aF9GVi^qd9psUpIdk@nigJwD?Gl!V4-Tl9>^V6-iw5{@% zt4#g@va3F!m-(hSEHep+oX2lJ}@PHt~a>IW*&t^RjslMQzDSvtZjS4UmkR6H@QwQ<1Nl2*$ML*~O zcB)8U1mXFBmaqzEQHZa1i5FmsCJ}Lb5T11dOrAgI=Gp<50T2$80Fm-yg{*HcEN-{-0X&tY@LPJ}bPk=RC#}MKIo>Ry$>c-KJSjqSSr3zUF(d zONdeuVASpH@k|AO_S%pbrm1K8VL})X`{?=}aInNK{v7sAKMQjWdujX=hXZ4Rw{iB1 zF})s=-VtP92>Xhtiyf7&NC^$^Ss;JL#|_LUf9VdtbcbKM!~YJtgP{Of)b`Cv^C!_k zd!S2!%$jgaJDlfvnbl9d{|#~~D_MWex_txlTSN8)|A@Cp!H;X}9z&hWL+KYzINTnG z-m3EJiuZHRV(mX=CG;eGPPKa%C{wrfGt^E_KDqifv)Z(w)Uy&{i^m*l?2CjC^{qO? zMTpW=ya0-P;|pAG(x3zk6o3^Fgn&f|vCfMYs_etCOmN?f$5t~zdgtb|$6@_QT8@C> z)ey6PJ>Cp$!PF|-A|cImYBF>{nKr@G-iTCpkWXKj9y_SO&L}f~E&XqOUC7@b3Gp$@ zu9v~1AJ^hAUsy&Vh_PPgPC*X@^7ph;eE(9@Jxva}e`Pe-?%#5a`MeWf?YSslSpl8@ z#9QX54&)T#doP-T%3-Wwqc|O@^aqzwaC}AcJnw-x)2V;<6!S3_gQyoMT=Z$qc-W?R zR)gAloYYx{i3sXS7;~!&H?D)T1;o|8P0u*IzQ z(EUZjciDzj&;iEQ^@P;A)^jpm0igas%YiK+*5OALUI!t+=P?vVA9AAP1x7`4=s}rLPXheFo~nww*GXW5IOra%F#LdOHN!PZ z+b&M1hi)WIZR!07{4$7HNRd6y3xN-hGe_}AHb)PvLwnunUe2~PC(CqHbF$XP5g?QL zew0r2TVaKoyu@Bfzu0&rQjE0SY)%Q=_D%ecnZFkD*iAFYHM zkX5MCHDuM@g{uDbq*~CvV$!>|dJs>*{yCX1Y{k>K#r=^Ul(8r5-64ItDimc`f`b0! z{D1&6<>5<&3Eq9cl&@vc;pB@_BnCBS-94<_+&rucaM6BLE8cvh(NP~&s1_#ZC$i5# zUZxHy+-3)~OuF%WEA)G+OM9=7d-~Mz{05DY&jBag##+;$LS?n{?FasAZRtW1s!=9W zt?S(1?jR>YRebZ_{1H9q5^6RM%@_i?Q6TXlkLx*sr4j^-9!YMvWq%Jf%%!?)!E@$x zr}y%ikEceOw1C@LqX1)>HjNbFBx&r_dfyz?W?pqvC1JT zYVdUonh?ZN9O|DWb)arf=Fs;3X=m*YZrSs6p_OfLTEU`Fb@)ri&RU_WjvcjQ!wnZI zHr`8xChQ~$jgk~7l7|AY);2YG_2HWN&jDaOt^!ri_?AR=W7 zMBUJ#>p);quW)9nH+7)c$zSz*NE+m`l4e9soeu0o^V|`d^z0R9JH**4s>4@ovNpO5 zwSOzQ)w=HN@D;wFIIwwOxNv5oupKJYUqb%8007Z#sfm-W>vb<#Dpn(=#ZNRrCCnp9Cz zMe(amauYdj6`EeORa2J_9ASZ*Jw7L>@bi|B3!XEe3w7%5pe}oO+~{#(;sLtQ!R!)4 zZzu(90o6z|5A5yB0b)M;kYpl3D4c9vM~WINfMt-j9J_iCihOHT@wolClEAT;tO=p= z_QL7T!b+%Ve-EWu$_@GuRaic7aGS|~=8!~fIt*@4p@^kbMxEqD9c*u;=5UICH01bp zxlXutTbR6Op-FGu8#&%IGu6}%Z5s5^nx8MGYMjY}Lh+R^JQt*zkxoR}Ika5@=99WV z+NQwYZ7@paRUyZ;>3DUmDYT~Atm)8ITQ@v~cCIvp#o@cWoSFCK!E|HWw`=M?7AamR z=OCCs5SR@0@?+UWFP#j!V@IcMX@`2jJ&V#N;2Xy#&?YilbqEPYNRsNv0Ui1K2E#t}6yruV%BR8KC%|DK2qOE0p*GW@J%^^=L?P|xtS`go z?rlu`L(iEiZ7%sh-!7C!toT0k3XS8anFf8cneEH7FAtP&BE2MqtHl&iY@Ekh zgR7v0z=MohQ}2Y|Q_h-yj3$L`fJp?x{eqO=(@}@anh<`1YkZYU!kM-2gel2|)0f91 zXT~BepEiZY#``W#*Wg&JuFy7rE4H3Y22gylf!>*`wb5^8FjORCz=id$ynRwN3c=zJ*Z zr}AKjqrggrPy2bZ!7eDNt>%5kCr5)py>d2`aLGYTX$wizeUZ%4`7BeQNe(fS%IC_* z!FBXX>Hs8w@1E!_bXU2&VTUf7Njr%2-6$L1(59F_b#W+^@jtCHzHx_I$+-VcF;{X< z|GTxRRK@DdJb)aezEIj>S90#{W=SvFv0O#%q%%PVl4>!e3212-C}4E)rPA555X-?P zV1E&&+rGl`URwt5*hwxql(~UZN&8jEM&;^3pCL^|f3Y0Lv?l-HA+_GN@Do;+ZIIgG zTB4M>p}Y%vEokTnJu*^E{-By`w~abcv{e7`B9&TkH4~p6pCK8uZJq2|qc6)G0rjE- z-G3S_C)^f$(UzqMN2!{PHwk5O+%;R>R@NDHWc(QyVeP^(sC@4PxPk9alml^_@#ZZ| zQ)2kM+aY}k;eTGJz$GWNis{&5tU@P( z+Y22)bS@N(ofU8>`Ix5BX;H#a!LbL557ec>hQ%Vhk6OiUDN3NO{qp(e6T+OzHk6)j z^Gp0dwFAq~fG#{Atv6WU*h$a96n|Ga5l|EIEe@h?5q0ET)T$%3f7_^##Bnp-^6c*q z;-6B1Io?#(miX-Z+~w;6u{V30$4?11KnJ8?-Btp|88h?PDH|w15SM1lUVLd}@A2HC zB|4{1*-jdCN-`1-mrb*BkRfzmx7)P_PtO`j)MkRtL@N@Gg3h}=)9h|sPg^36xKKR_N^ZH5*YR7V$rW6pQ z${g6V{c%9A#Mp^LfltuZ9p*Kz!HdsG`+$>kz3!(;uj-{_H)z450}RGcMZ*L)j zxgIIWwnb@q8y+d{a45MP1;q+>N)Y?LNeN_))HOoO&v?_AILoTp#N`Y)J z3Q$gdF~mw4I+0(^G`9(HsC|Xu+0ZkUP!J;|F}t1taH2!>KG1LuieK2$hV(gZt;rvj z-Cb*fjW!~i2x?@Uun*Wa6{8z=WTX!l(gdvzz!dsC4O?^klbjdr$XmiX=yb>X<{;K4 zi`2OS_2p@Q_L^G<^_i+i-D02~esdb=Vl{_dw~&l2xp7PPn}AZU(8CG;Si2mSB2sx- zoHz;VvRm#cfrdZ$Vgb)%C>wv;jeW&M;$@`WL+^p99CbE|eTwSMIjkR3C$_|Dg5Avy zO8uP+p70#%c7)XU@wy7PYHtVB$Os{&8bKqp-}3JuBriSJuXna`@79q|KP0SpcCXHc zzq>^=lLLZn)A(M#g>&C`gBamOyTYTn8MQTPhikv(g04cr=r<+kaxw@4eb^vZ+C92l zm~#K>ByKC(Y1X~Q4aKfz;4Lv2y#y^D(hr^TRj%H(*nwMEDXyZkC3=PY_KUV)5q?~G z2coR}5`<218ys*an2(p?n113=-#kGRI~Fwny!m}KBOH`X#gqj+>g)5Nn7@7UhtPu# z#dt?T6^A47QVKN1jO~$yEiw!j5N`)RD|JCxd6}3MGq1&_@1XutWWcn=ly7Rvn-JdV zi+2SWDDu^;OP$B`8ej*q{}ohjQ9~fG_UVaUeI2=!ZG>+(B`QxicYjLz9)DK1BF4Dv z7M>U2jqeMHm~_Z`Q&SaG*s+kbXEj%gJj2r7H>zOh3q38zvU{_8W{s9lZX7}}}yZ$!lY2CY^qp5LZ{a?hJ`+~+s_MH5wMy?#5A3}8alPAvIv59@u z@mWffrx$IbI{yJI4E8h3QGX#iXG+I6Y`ny}&>%ohpr=8LsmIVKFZhpaZvxZX6T`8>{^Nd3?n3X^_)D5t2qbVXwV|-~euAn+ zlHYK0Xabp?u^`%_@`3E*DT{Bit+a8XOjvr%p7sUGHutSb-6lDbiP_rY#PZY81mZ;S zQ`OF=dnH_{XSTFKkKM|v3zv30y~A|(5JTC%i8Xa57Z#ZE0|x0<*S?LOJFL&^?D%m1 z(}!u}x~|^%G);P=D{;cnabjop(0o@oj2=zuRBrCnlp1wvikr?Z+`hm|Zwkv(=fEJo zn=VOgQnIqv2Al(xjm3>UZQduDg?zhS^m?!;2R&MH?yg7E0(mccLl(BhKh&t=i=snV z4Oi3O^v>Ht@)j;O$LN{pj$$LR`p_;hl~bud`Z`36iv{8FQLDJ$ScUn2I8*m;DP1a^ z0d!Vutraark0VMHE&w!mhZ?g`%|`^BT3ptHXRh-ywt^StICINq#U1Ck;1Gz-;N987 zm>__nx&MJW&()y*5ia`+UN!g0e}FRn3Z>6AG!V36R`|ZH@D{XN&Q=0DfegCsW8kHm zklEgjEKNX@#xc$T{oj_@*GZa!9$-36Gt(ngk9P-D0uKtUHgTUqtTFAKY&>6V<(@qr z#N-#yWs#z%-d9A17Iv}iRk5-18MUi?p+b**O3@Pj`_PU$ti(qsV2XRRzNX-ajXOl+ z?&y0WIQE2`)=x0DjAlb$eq3QUSm^qwC2-ES+iNR0nRImTxICRc4L94jC96xr=T>|s4WmEaCmm>x8N zJ0Ngz2XP6H>hx%-Rt(~YT$<2tfKTTuSf={O`srKp8VpT@5v~Gpb;oTe-lRNZ)ku@O zdp$z(f^8l;1>x=^xohP;MLj`Lkys=`P|9sd_^J*qW2!`*yH+yfbZ+ePPg=Setc~Zv z%P+Ish7K!IiJ*$MBfsqgG^CRgMSZaZd`fO2dmyGW?+}C%utl%iQmW$*4Myz@p;yvI zKW~K`Y1cNjrrpp_O~3BaNAS2gvY9$$UYh^zrryuK6MWl<^sy6Li>3XLodb>tcOB?v zv~$>Tsgzz>OsaRgY_O5-Td%Y@5TWbUJkPpR7edeRXkf9i9O}AOiG_=$gI?&Y%MT1P zaU1Jun$maqwlx2mf3QHoL}PEvvcAR|fht2yP~O|Y$6R)T3~u@O#`{4pd|2Szo$66{ zB(Pq-Ow_<7Bq7`EpwDQ8llS`OSgk4Z;W~dUK)p|QjiRQ5Ae~(^=gGd(D(K%B z@J+r42qL>hW6KZ+`35m6awsIp0bFi-keNMvrwWEjVTE#NZ!KG}#*)ak7!lAsYj^WT z$ONbka{RYtEF@U7!H@X-i7XqX_`F^8n)RtKz)KnC+oAc@W5H#2CCl1pe4Q6hTztuv z>QU@?70ixJYEUc9?`_O8-(V5b`i78qP^kl6gy=Qh+u0*a{}OZ!dj8HDI&Zb#(^1$B zj;xa@vdL-CMFjx>Z@<;USg*JiXf-4CkA$M~`m3Jq(e?n=?(0%*rV+`ZhEVKoJ6-Qe z5yhKW()}1d_SqTG2FJ3c2AWs~AJ(IX_Np8qu-s=oFH&xg9M0hOKNFSH24-p3;D+4S zsBtIiBDE)Y0LrM@O783I^#Hq6DU8h&%CNPgrhAu%J{?V6+_)k4{i02u>1q;(XiuMP zX5~Cv~vVCxT{OM z4;<6gdruoIGi|GQHN$5})r@?^vTvRp+>=f_Um6rXJKO1iK$7{}oq?-Xfxbo&v4d%3 zM!iYe;z3->X6jmSseNU2t+zb0KH zB2>IPt*AMeURDmuZiue4706X1n6YhoY&{YgL_zR+&osVCQ8=1V;RFuyXu%VgRwB7j z$9I3jb^xnGJKRI#38f3lQAa7~IHBX}pKtDK0n*Uhdj0qIYd5J;B;BTdM%+Trey(ks zQG>G>XdAq0(TdIMMZkGmN16uCP%bMbk){BC8uGVWQZaC=)iegm6nnSca=tR!1R7=U zA7{sMy@iAJiJv`J3(Zecn-)Mpxib#EVugaxJN}MW42<6!L+E*ACqxW+QpQTlJ;XE&y^Z6ejX{3zvR#+>*xu zwfnX;vA=6H{+RTh6}6i0ns$fgOzj{w-c^71>z(XtEDVx&BNdI@I-hYL+7t(?#}AKcQ8lpIOIwM=<4uqA^9*?tUu{t4dIbntg^1v z%_A>f^Js;y`r#vApi>ka9-0~Q+oqTlfQRgp^SpFv@l1gUu!OonyA9Wj_v#2eBw6+m z%^(Fvr&rU0k!l)~B!9#iq(%X&0`z{glpQ~IL2-wb|Igfwx+D#WY_p@PGM6ZWDX6_E2n!}QV1#2m-^i^3LWi-k4I2<5>}oOmqh}yz9dToTG7p42 zHV*pkO#5XD_RF%7u2z`a(G9^{Sk;f>xVYOXuZOTfyO<YIL2ZOnEtnq;dW3&(GJ>}nhigF zxz5zGxh1^#@aOH8XIEY!_$9)?f za};PqoL^GuJV9;zRQ=T)&AC%5Sd?)ilWRyE15@*964^Y(xm~L_&&?f22hI=AZoY8Q zf+|Psn+oc@PfTij>vwd-0kaj&vLIX zm+@p_el;ZT%xF@xX=K}_68F|MLg0u~i4P9w`wNUBbhH#~kQwMQjzSz?yAau-5&Dfs zDc;0xPh>0y)*VaYh|2KHXiLj?I@Mwlqa(L^oirvYv!BYS+?dKH3k-CF8{z>R1T@>s z7}|bfe~}AXDo_4%$mwlAGFJg3)=Hq&PG%)Bag-AIE_-najv!^^}f9qgIr_2idynt!}z%6^FwMv)2#-k zh{#L~cC#n<)%M_Jz|&&kLq$8(M(_1}pXYcLtQ`b3w5T|Q(6k#Sd1`{^thLa1U$He` z@>d3Bdh`^X8hgUXvtFvNoNnFmjX@Vn{h2@Jk9}Tl>ZLR9okh!vcC9`sK+zSrTW6N# z0zv>lZ*0Fvgsh<%;BRj`aW-Lb9NPj(zK2J$(!%vlrar)@^ZZI0zYh#rL82?utLp#@ zS=Yn*c^ev{_^LGM41aJNG!R_`jl@}m3`B^$W@MvtnS1pcHCpbiPl+-|L;P;3!8-8^ z8Y@4F$QYLBO3NtxXWfL_)Ms`>TmrJV%Go(7>+t1{VY{i)shb6J#`dX>#a-nwQSQgr ztis=sIgbwzidT6Ltx5IU{2>5+6R*(9C{NA^avRlT?$nHRcWPnpJUBUZNKWi|2!R~~ z?W_>GiW1Bh74Nq&8mPThw1CNzh2Q-h2^^{yGigb=iKq}h@yp6xE_I^JBLx5illrH} zCdp%duUY~;(_YZ5?q~a)acS^vobfMzpv+)VEPZ*VnRxq>hR=98 zo^iZuNO%H{$Wdrat8TIQ`BKZJ$}f?`9P`(|XXF;LXJ)%)Q{^%ga7Vr}fXF8*el4Ne zs6B@uss%XEw)O#zyzSDP(!&?E8)*bCH|Ci&;(b$cGb!)#;=?2H(M-%4BrzN~hMHk9 zuqiX$y-^l^HxT$5S^=l!yYH_79HnA!C%FgWs!{0Tt_3O(3uEA=xQVFDl7tKD^L1F3sfNn~0{q|3q9+Pknt@Ly;hO?QQ}2)3 z2Wd;aw+f^oDhd48vOWzUNiAOKPl=6;%Q~}UOn(xqWP6?7j45J6TQR6T_Z#M4R+F(76E3_f}N&W3Lq!~ z^5jqb&VIBH%Y-Bjtt42p&M+z&{psj z_>VsnzCIY{N7~n?3>1AI)=ksYK-fhO(v7pd$UsJ zTA6dB&97)JrNx=?AtuNLm8>s72&DyNxoT1GDGQUVpOA*TOoktbqhpK#SD^0FkT&6v z1};^7wB~vje1;Z?<{u&8M#0x!pERT~v>m;^FZQJyAWCmB$`siFTlB34w$aLO^*Dp3 zE!o{Ej}lQBmwP66VlK`Bv3LR@rHt^F_y#4AY0BGx0Keg2_ zdWhtcQ}9WUuiY&b3ZNhD0dq|I_4M>D*Ya^Wo7xDG@p8bJuAwhwdN|oMe)C`c>Q5tw z&0CbeF#}!KOx6>g&Dp<3XV^`ZgNYV*{J00kk*|oew^7P!g+y|7RlgPAEMvz}t45wH z9RLeOYs~KK26Tyh@gBQ2=DG}>OQy;>nO{KJDyRwRHgC%n2bhkZkdv>~mJY;U@VsMN zKJg6@rzcbX%M2QKGJ-(Symun_lSc^u(qH#SpM-0E-usJ@nr?x0)HTom9P@C4Xc0kumpa|J|J5;cT4=DX8b5tH?jmJ9~chLj-N8jT@GfKrJb~+{ppQtt0 zR)iqW2YWrR3Q)EhW?DXJ3_2dyKXQ2(MdU_kR_Gvoz^CMdEqmbbrs-v?pchDGh6^wT zi~K0ZK^|4#C`6M*PN;DoQ2T&baiLU!;1u%{H0y8+ZqE_*dv~u z7T%*Nq5_tV(oa3!Cbzfh=-^w*_CTmG=2Yn(LAmpA06P@}PCTS$hI# zX@lBT$uuKbFT7106OJz@pzMz!Jq_aSs!qS#UzuAI)HqH01~l3AsT-0hpE$mDY;DJ_4aV#QP}+}reNUqspCL?K+JxtwIT6$R)LuwlcFkLOOS=*jW88F(A$ z?DA8RqdvFRRv6wo2(qAw#qPeP6ZW~$6~|r<10Zu;t}O~=R3cJYt(3Nz$e22=x{cN8 zJ#3YOv~vZs$)SqGMNfI3&%z^wl<0%cgGCp#$NBMsshlCA4ct`AqW3O!BF{px=;^+u zpRL;SJBjRWkG|b75oTOT@e}>GutwsRoB6Dy>6HDwPridRE}??fPOd&%7wzEz%7Yj+ zn;!R$dQ3pWbHN%UYyNiJD zs81EivFU-FBmvP+hCg~31zL&7MOC5u6wp2gO0YrfM0Nv8=>rK#@{#g|&Kkvb#;^M^ zb=5%)07hAIna|z9NYtV*3KXuSPBYJ*$odeD@2 zDsF(4?q$IF6IMix!{ko!w1{y0L$&mMhzRA8==qtZP(P{c{Muvgvq_RlOd~ua%kE~d z^UF#D2<^Lw!d|lKih-JIL;m?fP-7K3C-1SK3{Wvepa(lx9UC@{^>2A^;Im|WtKm5< zwAgBJYYnLMI^CyNSJ zTzFQh`5gd2CIpC4aIZ*V!PU6hD=U{xRB#gM?* zQMg*XPyZ!dCXF7vHv#IL+PP3Z>d7+%wsE5sUOqK!G-iu*!(QEvch50c-+m(?A@W_n zkDO7e1$kP*A=3Mdis`EUdwk6o&+Lt?pmF0iHAr`ux^v1owJr}TEeT|PMPz4+AWdy^ zkB`3%o53n0>ABOm5=3n6?iwH!SX2L}>)2m(`&_N?eO}@dMT1!T(n;iKa|rA-^g$Kv zmId8VpOwIy?}&Dc&%BzgWOoG(<$c`zw@IERo<4=Cs^uk-zX*k#*!Ks24PFEV8D>Nl zI_P5k5K^Er(CimcCi^+fPmMOFhXd`Ap5LXreev<8L1UMa6+7T z7?a~&r0%$f>gTOGO`DC3$=pkgeXONsQbW#Qd+%d@A~dY1f3Lt@s~~ZyM?((}haY4K z_Tv?}W^5`rS=D!$M>9B7?bC>Ion}{s(YNS4||S zV6!rLaHq{dMMjIdKX1v7`^yYOm@#hvyN|_Rc_=2C*8`CZEh_w^U?m|ANF-WU+_b@! z3tM*umE708;KL^ql_#j0)z8y%^EF>cUbRV-Gnu!h64bi1vlI{?3z=9Yg_{(r45O&> z;XM~>g0GjqMVGms#9m5x_Aub&#(u+=f~MJX!mOk#`*4z!f>+K~eQ!XXbD9bQ;eHO=Sx6i{X!OFYsR4j_JM2r+`bDdeZ81g;X%?$?TnY~=-ZOI_8*d2#A? zVWJD?2ZFH41D1z+fZm&R_}GI4&l(4K#|}}*cTQf4JF@Yqm(vb=pLmyAp;17<--U#R z#ZF5)Us&W3pdXA5+#qZo5+W`<_pnfD85GtwbuV7G2g1r_EFqj*+mX-Hz)oU2h#Si z-A`p5y9&&c3|}i$K6oAM_kK6!@r3grja+TwA)#^hy~uH3m}#*t&bsiU0%>R0J-83m z!B<&G7w>`aNRR1pcO|0Kcg&VSbt+Wa^DChjpS6XI6J)kpDg5EJOWNsOtOTo5#M7!o z)W!y=iKNK*!adQAYA#}b%Z45%VJ8cExcER`Y@SZlRgjyw>o%cLoaSH77|LB;sG#e} zvs!iGCxr$Ug+pO+3Wo_sahBF5EOG3c)zUe~1Smw}SQc5c$VAJFGg;c|Gu4nErJBwb zYgrXP74IA$-ERj{J(}x%uXEl2)4Xf9@RfP~#{6Iic01B%>BL?;!p9))n}c%R<%GQg zN&<0#LfV5qUh-#lLxHhC_uc$AK88JFAxUVAbyUt38u5zQ<^~S$nUxo|E0{Im5!Y|& zRTxWOf;53TOf!aoATmaU#|oVb@iv%buOSYxo@Hh>01nd^xU`deuNsvela>>_A7!33 zWgqlHzP+FDG-NP^0m52aYRTh1O1`4ADYfof{T6f`IDnCh&ziBP*9KRa=^h>9I_Dc@ zA;=gHGPzU4-bjghHvdJxp37qV;0HqSsllzikW4}z_2TVW*n%E(>^7V_)Ei-THK}sb zTkl-PV#0SRg{96xyKvx+=^Wb?=B$lB^w|5|=pcQrxU;%9!2Yz23jO+o$sjw`paOkR z&BlLj-6f7_`l%cHt`$W)oy44K|5Bbzq_>x9g)!9q-2vOlDC}A2s#+701L#^(rkpLa zG`;z9x!G>qb8vfR@|?+4?Z)RU+{E+ty@sGWzwq>6l}R3c`o*i}uFUL+ z&AA1>ME}aK?F>R#9JNYHp~s8C-(oXppK$Og=O;JKA03w+S96rZUS%GF3f?z^4t z2t3!a+~5>+F*FZj^G;EJj2<#H7vUeeBx-rIH$e?S%DM{I9jyX{_GafVbV~w;h@{nI z1PlR%>`)t_1)e@_MybBb8>D39Lzq|!_XES9Q`))9M`E6RXCbm zLAfj-YqD+X`;W$qStp`m9;L~{+w!LO`m1fg|2nDXnbs3bE-do3JVRpNik6={=;g^V zg~BctqtvAC+YQ(4JP|aJt~+YVM0t@~TrM*BG~9Q-wjLn1^QCnyD*{z+ZReL_sG$<+iyW{hjgBTR-N-H(BexfxpxH-WKlnG9ZU zdlB#xQkjr^CoV5^cyIlbHG+<512&r_#LS(U+wm3D!1kDm6_}PSLiO^B*3bZTI6aXZ ztuaZdik?Vq{qYk5x5S0K<03?at=;sHYZ2GF(*PrD_M6lr_@b6=>J`gUxl}_WN@S(9+3wCpcyiw zGUdrV#zM~ksZGK84)SG}-*H`ymx8F53rXx~LDJM9szjUq(QcvGKCuT13-X@4etAr+ zUG36HDvaIM5yM2h567)22la#?Xf*mHH1W4o@81J`1(k++03J5v%$0I$>Oj;8-RM}S zl7n)h11$FZ!t@0u{+a{xS>m+s?z(wN%5Wu9%?3|Uo4+L-(>y_X6Y2)e&MEdZ6jOg+8st0aB z%7gq+s%IDI$*9dSKX^R<40*%}%%^8@RTuJ6Ru@=V^H%CWpNTlOWH9Nok5IxPrpDl+ z;41t0_gw=)f+u2`DTG2Mg#&VejXG0xudjEdiy%;PMz@bLo7O}?LYUFyocH5z@o|d`Lh?Cb>qo zp^s?A`=0mIO;=d^rB~e-sbBO@Vc7NN8=0b;!1$*9UA*xBxJJ33#rt*xr~o=!3-8)1 zvaZ?JtBeIym8B{ze;0HuH<=C2ZlaO)Dz8^k@SokmaWT>JG?sm9?n-X)s`3ADW4GKF a%RlE+?l*e6JNj*aKj+jmPv@v!zV$ze$;UAO literal 0 HcmV?d00001 diff --git a/doc/images/plotjuggler_select_topics.png b/doc/images/plotjuggler_select_topics.png new file mode 100644 index 0000000000000000000000000000000000000000..7f18ae4da76d2470b2b4540b6d7af43dfe5adb37 GIT binary patch literal 129374 zcmd43by!#3+BJ$@2r5b_p{Sq&QYs~&fMS3F(xs$`bhk+e64I@rA|=ud3eqLr-O?Z> zb;k19`#sln-hIw>o%j3x__2c*Z2aE7L<*&e z_?Aa3A0MWC9C?<&XjU(!uWK%?6q}kB^N>wgN#-tFd{~;li~NE8Z%Xqzx*3*(6OMWB zznaojQ=&mn&b`=SD!kY+rY&Szok=D3|NApZBQ4Zyx+!Oq<+oj5^Y!+-x)7hzHAaeS z+xniIIy!2>lF|90eycBg-?(yqu_*cLvr-?fN$#+<)$uua!LoRA19;`pj8fQK5Io&MxOP8{6x+ zxH!9QXaD*7qVSf|@^VJOv>D=S&OH@^P! z&4F%47M9o(t)4ZNKB?EE?6tK&$@H85>-pVPrR63?erBW`P;s-gIt3-9Tnf-y4juyd-W-4z~q7d56ZObwEuNat*f@o zGhda0WwiDL-G8F9`z+IQ>wwTH8`iWj(L?*acQ}VJpQoR^y7BJ$Lxro3ig>l%Qaqmb zVkxS}1Z7$Mswbl@1?la%_wDx<&{2C%-(NgE{!M)6bdIf~qQotF-)QAshVAYP7}Rp} zOiE37q3(AxxBMy|);;q#itB|~0t%KRds7)1$$587IsLY`IZAirUSx{%7Mhv6p}f=F zEW>u?e<&gH?H_)4R`)8{8KA9WY{azL?O&up6RJ>wW_|t#-&6n(B-D_<^ z2qwPK;UINB=XyRGk+fQ#+r^i!WitsF)ow=Po^9vj?U+Zz&e ze!<>CIWfB^si4934_)|_{CSZLY8RO4@^+v^(UUBD0_sac$5 z+M38b-k%-qb6VDVlW2@p{U=jVp|0GQ2V>iYw_6A`JW`E#^kuuQ96LqC;H_xIFsm3! z>Y%b8YE?ht#SSSt}wHZU&v8l5;_`_0Tv z%j=f*euf*opN#nUcj??VJag_>S;a}8oeaDo8bOoiY(|fNGC%#?UYmCKR`}7v*v*46 zTkp<3V<)Tdc;nzaNe*b=&d|-6n7=sThtMrm@v`na zBDDO8FJUo8qUW2gT_cZ^Mtk$@#G8+gdF_HEzTHa_+>*W0@8#gt`aHb9!iUCpe3ndY zEo%RF6-6oax!vzgKeq?ZpS4NrkIri}x^OnRKet!n&%(je7H2akZ!lFP{&9SMv8;}2 zF0fu#`}WJOsc9`{iZ7~NR))}W}CwXtm#ntaDYyBC!2 z8~G(2TwwF`qznD}-rhtjbhtg>&vftTCke$_rioWtUu_jFuWs~+1uXh=WIee1?67Rf zgE0fHxQDSfPuicJ&@8yN999!<>pJzGi<6J{emP0D66Wy$>nWs&2z*t^O-lD_clF`!T3Ik{oc06e^CnhG!GduRoWI^%%OA^;Ui1f z=2DeoOB45Z7F79bcQkQseB-CA{Cp|k`qZ4%9`@ji`$ZbfBaAw#$ppS#TMJ>Uu-Ip< z;_r7TUD(!Pu*!P3d~%m##eL1r&>Wg#M_We8z_{FqeKfSo84QJK4O(rhoaf9~u3QS^ zI@q@F@~cfj-o2q^9Mfk9Zm-#N*_r=Y-LMg$Tm8&1@O;}D zEpC8=X(86Lz45u-N?AIsM2ti_)r!=LqLkquL&ir2Q?wn%cB7e%tc;A7cON^seqg0I z%R`#X){!OWVal6OHIu_Rlk?_5mY%5IQ0GyGcKI?q&oO0Yg4t*y=lv$gW)7(WM1ChwkE&T zf^_7#H5`~wERYLb^m?{G`89)ulT`Z09ZzrP7rQK3DrB)d^L_94knbVu zS`0SDtD%zAe6NREEAo70zy0GLX*j>PqIR4q6z^Yp;Baz#mEt#Pav8=9Z}x}{I-d$I z;R_%AzBiI_Z77#eb;k|ADb)H!Hl}flpS#eLBD~ha`PKPP(qmk-e>k^I^_`^@EU={Q zuJy5A*y-j{8g`Rg;<1F$2e%b-&);0FcQbTLCI8N$*`ubQf!A(qllQZ^6Mw3_zDdmF zmdd|{$`h1S&+m3@`vp7Q&-Le>wJ*Uq<| zwd1j)@m2_EIX6dlSTF@OJv7y38-0Z(psJnQqxwXUv`|h;yXq{6uW%|C?F@58suY&iO!n(8} zQ~JWEPL}SU)!S!AWkryBsx9S0ACCDiACjvTu0F$RmHMvktyV#G1s(b2g>1Y0Db`&a4Cx((+T0 zpQS&@d6vSMkAkY7aje_nby4;$P58IuU#wRjCz;DcU_>oZdjfg%D6@0pQLFM}-Wrfs&L-~s!VWVkf{vwn)_ELu7rE4A&YtN;3U6LgY zQFZh;j&LYR>t2{CnPgkF;_zoBO{%L;wmmh)A#^f~n8cT60(n`Sx|PRzEA?BS-K@4W z7h=BOxpwdgllfRftFc@<_BrF?CWB2wxzDBQHRz<5;3_S-4-cTMH%h_2v*{f__RK}D@;G6x{UO~#& zUh@}>vJB3gRed8e8o-yULlrw@U(OTdYl3h4#OL(==sK|@%lboI>3KSG+lpP}I`tDR zKKERvzVLQ7W;b?SE7bcJnHi*&+%EJo>6E(8ozk-_LE)Cc4r0_^5OLo80`+_63~y`>B#&3$1Rc z2+*f-{^u8~dlbUV*4IlI(%eP=#q=&;6cmg<6GhOG|M&a+oeAQJA$RLe|8wF0WMH(9 z?~b}sFbAI3qjV-`NV_s`;{2%L^Y@$Vxnedp{0w%}o5Ve6Pmg$gcp{Ua8de)AF8xJ0 z^BLLSxm(wgkoDI)aO6mKVcU%e$93y+f3^zW)6%mv{w;MG#{C&ay_*#j6s&A*xgA!Q zo{?SO-7=PtU;XiBKp>x~_GRb4qu$sT9v&|FG|bvB`FdSzn!eJ)c&moK@oAFzUyWPt z_ZPq3M(f(a-j=2xJ9n9wpEzy(x@f-t&nf=jG&Soo*LAL5-Hzd{t}S+xH>6E5k2NPm zNrqh5Mt3#uM{%)KqWTqeb@knvE4eoF>N9;s+miJE#(+}h@b%#|{r2hKzboe(Gfju> zn)MA0Yf^OUPbnm6<~42nuD`9@^7Yuq8-DMlKHf0<)!-Vhls+U7zS@>!%}p-&`=?;H zfx*H=yLi#7Lo|XmW|y6%dg|)x0y#Cd#OC^lMOU2czwvR#~HRm zOaA_RhjhNfS~krWBD$_UHO*)~LP|!Kw)9LjR+f!PBJk2wSMDZ`Ac^HK?V4Qs4<8Or zFb`l?tH#g*c?{_#gU=m1cI;`l;|ARhXWK3@%PR_szF)~>E;p}xXI{uEL zhkt`+l6)~Is=m6KjG38vZqK*x-@mUq;M#L~P3|Ux<@;%AD}&GLRgM|7e0_@7ocS}B zP@kwF9(+!>0B?UyQgWLCecvPM?RzL$-(L4&@@0|pc=CjVl2zVILm9L1@$&QSDF&Uv z1uyqVzZcupmTq|4$mnaPgqYaYE!#=oK5C4)hcL#(dHMSKj^$0ZBtFO3dZwms-?_6d z!hRvBXm+AKJtRQxi*k_naq$B*G-akWg5qXo=PqBqymi~QMEeyB5`07K+O?hQ>+4&$ zZ=YRgH}vuLeqa#Nma4~X{_9>akKwJTTVV!^KL<`>F3;;VaTxcBy`p3*Pw#fnOI-c- zbc@+Un;%}THd*KPtuTHq)ikRab$*NShj-UIGEMK{(e+Wcw@lAgu-C^aaBtqc*=niR zc^NZNrRDSH&1d;UMm4*cZJpVcL@fTE>hA6ncl+@}tjnr@uVTu>%a<;Z(D9q~EOtBY zILgNtbXxk;&m3#hXV0Edb7}7M_Vyk!*HBld<~KX_^yyQqyAzvIT1OIFQ=CF!xS(yI zu%poHBRs{8jeg~REORp@4E>Xn)$TOhtbO>~3kY<^6DM9^mW{FGBwcoMk{)yd#R5|~ zqGL_*)(fpVPeYuW=>=_k9oGKrr>4GE;m@|*^PIf0#1?-#XV?|$DfGw1pfjsBMh5&M zV#6yuoJ@0LWFIBv)#uyyewL0Rs|w-K87%ip?-2fHFJ&YQnN7B(y6J>lJISe9zw}|g zeE?TKe0VB<{ZDMBgr?>R0|SFNrF0Jl$5n3%=3CQEN``~--JyJ@R>NVINHt8oy}ge+ zv;6qYe+|fA;N=a}Z%^aYZ#(C(JV^CLHTO~CMNE^I*S<4yUn=wLS6VVnnX!QCbsw(t zHCYan?zfr$RW#jO$mg)id()q_w~$VnQj*s7kBtG%6!3~!%9g% zBE*kHu5VyK3{T&=YuAI(x{pIzGcz-!htIiScjm` zv=3=%lz0r5dLL(1OmW$=gKWBtIpR)^l`%=NJ5AwCf5|e!x;0gg3gN3c^7Eahw)W=f z)wvq!45J4YlO1Ka*{npl!|IIqujT~LgoK2m;e~|-#P$5A59T%Dg2Y`LW92BQsUO}t zTjI%ZJM~c`wV=&8rL@PrKDUK3b(M^bjY+9Fo?Lx>c&36qpTn^0V&2+<(okiP##z&a zafQ&ZFojH$lSsJ3J>Q=XF>I5KS1cl?HN*J$%EE*OB4q2>p$%!BO^=EYxWRlu=i!pU#(LvuC4WcQ0Nr2A!xTWt!$XbrBh9d7ZpXweN9d- ztf+AN_U#*Oh0vdoNLGcU7nmAO&C-2mWaF+y2-)u>C*N@&DT?I9%a^_5;}VJLMS;A= zeUfvtUxEZI&#Giwd^8=dZfS3q{&?e1xWgY^)8*y4;knY|o&1%~JqQ9MYChw>t@&#U zM@WwF82l(Ke2(m{VQ6^!_2Kg)?db{DDm*+q$Z$2U4zWBL4_CCcmlWj4;Q7hA{6xL znVB-&eVvBNLPN>P4?8hsmF~ zx$VIcY)Ns2zQ4=E*>*DJAy{jv{B7j{QYvINZ_*b=IVPU~^?AWGK zAvFmmpUmdpHagXzn|iQIQ6^VA4 zCWF{UVjdOa;|7yY&PsnGMZ%|cdT{GpL1E!(m8_J^%CL?XrIXSrthFz7wTO$q86xG$$mlkqIqBY99dz=h|DE?@t|3i=whOGfy1G9~N~BXB-aVQ<{96_!y!wYLg{!-J z$~AXxZtmsD?5T&f?_XY7#w4t+tvwwtNyPObwl_@qicSFNHtXj?Q(fUz90gw5;G+Zw%yR4ltRxdxlD-sfNe$Z*}%&(-)PS397l36@7hurxa5@XGYCpJVRM=cat=)<5neD3qHU~rw2yA8cw6? zNtV4iIr{V67UcG%Odj5|XFcY}ntd?dATF(kz}3k*HQSRYO2&q74xIp6A%Gdy!(ysS zQcCIos?l)faQN{H7yPMIt-ilsb!Kq5h8aD5`gG3nPzb6@plugYiRoJHrk-AB1}08U z?;4>McVq)>?V|D4i}^+eHI11|bP;ZKktl&mLq`{LNs?tW98+Wu5GVH`Pp% z!PEFU7t$X>Cg`FySA^Z{uDwStoC`p3pF_50;^6S=>A8<|N2CSQI71X#cWTaOy@k&G z!^7eLRIT}rjviV!{mvBCeY~mLnRVX5!2z+f#nI7ms3wB^No*`jtX#qnw%xghKcCDF zR@7rkfkyl_>``#l0U#=axSjEUkm38PA&YX^7W)3I3I%wFXyr^UT+$a}n78RIst`iW z*=g^QKI~k7Hl^w5>HA2XkK0mQk)P^tQ@{(q;fp_36;YJ0ygJwmU|3R7QL%ak!N2xr zUIXk0ElzHf@h;mbL3-P9PF1^^D3#n*VBehcZi) zDnxB4p4lZEidc`j;dkcuuSPe(V@~W`(if{mc70)qf^Uux}0HNh;Pt%VCZXl)Q_4=Zct+;mWEs`bi zVw<;YA#MQ5e1Y8OZ{IXCAdb$n^~8k>7S5@D$VL9xs{`C0I`lzgP#%VYd0&Ci#_lj` zo-|?E@bUE(15U^NvvnPQt;GS6@-q-n=EtLd)8Xs{qP<6a2D-2Om(EZr{HvM~6eY@j zWnmkgQz=_!Mn=ah)8)Uph5P`~ar^tJ`tKx|?x$hazr6teBN2mkH$TZ~c?^|pWZ!_$ z`@ejA;QPJEt9w;#Mo*&BSvHT!)-6A21FyO4eDt4m=W5(v48BFGT^VTHJk~U=NbC?a z2|600rTNT8yd;0g{;%j4|F^L6-(Q&VLjRqgn>t2N4Rhw3l*F!HRW~$rtVjw93i4%B z@()mRpkZK$us!(hpDB|c%e%?nZ8OGZ^Lym7kr4-zrF-opEUn-XFCenH$iU6DKg zS&<)#i=ESLrKQ(m58NX0DHFrhD9@P_6SQDHlx&J1lr=AQQOr`rbZmR@-~lOvP{*fs z&soM2+=8y&rlRac3n=xLNw1J*g?%dQsgM#V0bXJ<_il-Q;) zF0I|7PNZe#%LLH+{rdzzKYz*KadD3yH8q~dZKi|ehkCj~lX(scSg^9^E%ga@YG003 z%NIIy=3Y-?2|dfm9U_RxIxVk9A+PcEKCXSgP0;3d=}hDMD|?O#%v9=8pS=X2OD$j# zx4Z^QNbpTQ^Ir#1Iufg@J4B;}S)F5hf&bT57W;d9 zjcd{r?o39_&4VJ__8fqU;_Vo_Vqi5fpOcf50e0+Bal`kNvA8)J&_AQ4qXc65ZLo@g z5=`Ucli3&7pXzW0?cBSUZG>ZzWyANvE^_jc_Vy#UZ{MENdA@`E>^GNnYcu@=xa+fp zOAdQsMBVgZlBDL=CdG??+i*Gno>P+Y zsPPr9KC7H@=|71HTQ5N=VbA@2Kqgl9quugs!xxnhK&PPeOpOvUezTD$`T4?-5bOYn zC})VjwCuJIK;;Pp+U8RKv9qqee$zR+WO7iB-n?Q~SoAHHD0M^K<0?qII5O=ivW-iTYj$s&g zxK-b-xg>XY(qa!fw}=P^kTV^yLdvnO7?m$n|3T(h2yuGj^ztPnqH?fAfV+>V5(H+! ziq&VC>j4XjrWQ@E?{c$Vj42%wSrfTRaAYXiiEu zVIF>b@7_U39`CU&L5^xsRUB3(c--cx*c8Q3TTZLxT@-aDJITk_s=gfmg*#IvtlE zUfvS9#mP=nWoDjS+r|mC{(7XMx^$K=zPIIST=5p@yAD_-IRnUu?yX z88-7VcjM$aBLOb2-njAV0kxC2udgP8t=(!Owb}i{hZ6ujO@LO;Gj%uFX`CKVtJ%-{ z)nbnO0Uhw;RWq{`2+QnSc?NpTq_swQb6#~UA? z*PkRq4nvQ6Nj&b&8})-MvXum^57#%&MG>a~^yA9+eD#Wp82FDLKLGHlAu60BfFGW7 zTu`ucX)r*|9dS%N76j)UfgX;7$`J1dRZ;z%ep>^QXQ{Cg!CeXYW2P05a4!P`g9e63 zyz2}Gbok^AUyk)ZW9+eQgI9^iLdbqFqhMo`Ma+t6SaTW}$BpABPZr4|&hCP0Me5Xq z7h`$c!TTb?;fo#D=NL@s(%YH=+G)DFx`s4@0s|k8cV;(pxOaF~P^sBHP|mTcEv>9P zmuArU$oGs)`4Zsr-omBs%toN3{?+9`>`djVh6uQ?x4AQ_b#7-;}4hp#h76>q3n8y zF|EnPKrY0k$IqW{w3^CYbO-FCzJC2WZi##%;0}664J?-I9TcP+C!bgVnft>`!5(&m z#G*M|5H?p-TzvQvh2ER89Z6C3iXI*wNCB0rQ$Weds0?mgL?tXM+x5hJtZ7qg z?o|*##GpHtHOX$-#FTE=u3fYjt-Ju=Q9>?buAh#FzW|!6gMv0bF%d2GarbTEwG?X= z5)jF7>meGF-Bf2KpjJY`OOR~;R#xT;q0tSTqOYgtQlZmc&L9afaq;9wjc2;-7gZql zxkg4FN2B667uOqPgU+T4htEGEuW2nZf=D|MK7_-yG&M~V1KKq*aK>( znD+QOuw!eUefE_gpv%7geo@y0C#`;(V`5=a$WjSRa^u=q@d?FJ?+1b0K=p`f79;M^JqOh4oZ@DdEnq-b~f9O)Kl zs+f<_+Q=O!oD#w3T!FYkz_V1X2M@)_#+QRq^BMI#Dar!tU;6V0H?y%(>}YI;riI&(ni%2Qi|L%_+DaxB3uuscX(vAW8R z9pmHU(6^G7DvOGW7`K<&tLZg=sY1zF8c(jVnkk}+mW@9gDen0Rfs$#k0V(tWzz}lE ze!P*ohQ`d?T=FT?wPYO?6&1F=Y|g8tLc$5d6BAX{VFHG&WX&w9IT=MOSX`wB!}u{z z9dE`f*REY7nKdX`1&GZU^}Y@TjHgp#cMob158d$YLuUr`vMo)jnV6Vn+w>BMJozRt z&;@u6`vU2h#0X+5!b$gTK0eFc)+#z*I^`#d=LUlzm~<^HXX(~6p}JnNvf_1m;1wDw zfh5XW-Z8ms6Fa7Nt1JnRT{S&Dn)C8zz*%oEuO}fPM+lv*0D+1Q4;L2~3G16nYHDi0 z3xx^!>%n?qh0f$UOVhnW%eSzZG=Olh2z|rDCAL$!0SWT));}a}DXXX;yKv^`UkI2B zMuc*LSCSUqhp_y6yw%5<-o^z@9};8>Q|Tn1kkyXT0gLt`N}ijU{;VC3)C2(FN<8SU z-@Hl4sRVh$2HvBiGaOP*w3P_r2$U9No3(?C*5v`U<-uVvy-kgT+KRt(7YN_fFF?-7#x;1K?5TJMSU!^u2t@vd3u+p zhsOnmikvUpSc`A*p0yL936MoUspUJ^tuGI!7V>_bbsJ3gI#2gF)C}#v1#^ zU|Hh(w{MqB?SQB4fcuBEQ0-Y&vd~%ka-S>c)ZO=6p{4_v^dQGvyXLZdmHn@TQxZV| z^3?8dc3>jSEj^tlF)(XJ*7gOdsNg4VMql+q1OLW;$1L=wWr#w`Y{l!@+fc6N4V zz{JmYqLe(Q1C=7P#>uOuV~ephbU;AF5{Py>i(qpVj^474Ds=;DtS%vg%!J^N1BdIynx8ivXF*0uCLQ6-R^$L){ z_)G?NqB}VN5*ukfH?-U~89!iN?Lous1bkKt@=9+#u>XBzBwM&Z8xU7PLBU9CGIN-K zFK$c?*bBm-aOGEi+2!nNxks6%-PEdNVhnE$~Iou83i8gQ5ctDQlc*Lb?;`!lk^r?Sb~ zl1#V5-ShJu|79z&ymURPbT9fEH^2}SzTUrl*?BhMPJ*f+;H+u;7+TyOJY81L5mkeV z+E`@8ISb_V75{c<5c|DXrJ;B&hCZMs zRMFMxLUNK1A3odx9&Eos+Z?YXj>raz8-R4X{ECoNa5rCoTjETGw`0!0fF_F16?7JW zEsMIl8Bo}sk&Q8kPUr|=)ds@b^XvuCFg(G+vgZkyme-p%A}F%)U%&?_Fep3bP!a$m zWP%}EE7(Lz*PzrrgGnXHbodrZhq0;YarhQ8GI$Bo1-9oERQ%oil`H;jH4Bj2N(Fs_ zg36F~TGI4Gt|Vy7%2I;eFr$TzHpYEJLqi$+bb${|vgXL02YsjVRy@%Atc_RV0pxs< zo}O;408))!m(I_(mkG5SaG3J`hehVp?%a1UR!zG8{%wYiKm`F7G~PqlSwgx*&VPqJ zfAGw`&m`|*0b3qkLQiH1*`4U`Z`!np1VD4&p+hfGiNM>4`{HraKs*n)f}pG1+$3(l zQ5wDWC2AqtmOgOUOj}d4XLPg-P8XG*?*?vOF4-t&Nw|~xNTxi1y{5>GYR`%7%Q|ju zZs4b3=nX67L7)KyU>PyGA~wJ<01}<@uy!+acz9}z>SvKD?m|xA>{4lgkRjYuuqiMd zJ^BRGh_v*u`3oJY+DC{xXd>@tV7LvZOyD`)1BAf}At7tnk1;~zIY39Z_Zzk^tQs!y z7Nco#s=2}2_Z}XwT|3e~B|F>h&^*?X*uP~>^Tp<=(Q#C@jYY?e64*1Sd5zvK&-Ish z*1x^HB{VdY*KvK7&aeb+MWA-{QOX3q#2!7Uxr)N6G1-wx%WFh(`*w|O-r7nPG`9*= z5?-^BeE=*(5x+MCpO*HohG;Z8JrLM)h*PDG&)Vouxzh^<1H1P2_ZJc#G5ls~(4fOq zRaN!kLW{HS6b{fuDr8P(0W`ICk(r%c)_uIb|#-MY$Qk%pr zrodSP5Cp*#)y&~m&!AEOG(H(8bHikTirk)tIv@pUF3Vz~JjZ&@YQ9l!F0~46sC^6! zjy#r;-;}!@nlg?|EFR5fx8aYy7hM2&%qFzb=f*zyi(QJzhoBRP>nX*sMXAfhj_CS= ziBCN$2nr83Xw+Fej`lGqwP|k8Dl9fcm@sej`H<8AXPoJSQx5har*@C>(trfw#nBFecoe!wYPenLIB7;m|3Vq%h)cI4neF_iFGI!lL^ z_Y;PXh4nghR|HEZ-998^dI($y__Voo<1!j3#ZNYEVJ)x1Y(l96>AzVOd_IWR`2Di5 z9Q;eD+eDLQX!iJ3_a1L?`eVnB_kZe*hD!Lt$%)Hk;F_Jiee~VP?SOrnSXIJA1y=tP z`_}EyU$WhGII?aFEo*);9=3Q)qL^+__2Ie?A(29= z)dWi7b6A+G5w3@05b!1XUi1ObV~$0$2wvmONJ8jsSI!@Hx{RB+QL<%et!!dd&hRqK zTV`su_$mtkINFsf01c4u>;?jb5WJD6-(B-&M1UU#h9>ZWW_R>?_}k!yK{Nd-2=8b| z=G+#+fj)zqH*X>_&=qnJnmz|sJn#ty%!U!p8=NZEqso+5h?d z9e@v>fWMN(yC`e>joo|pXncFJ3A0bAoJbN+#!pLts;=ly%z=*>Sz1EF4uN8eU@(?0 zu$F|tEMPf#;`s3`;PD7(sN6M)kFm6#!s{8<3_Oop?kBGP=}jFS9nJY&cXMb|j#xGT zo}r}nbi*j@+NG5h=}Z%?s~)tvsuvzLoPxD%8p19l&!H(}k|P%$zlDrM^g1B0)<;V- zlMr$QW?m8%0KLgA%(p@_;xA-(%}-bg%s$FT>yhh0!B%1gAsxUw*o(bUl?Y7EVY~1c zjl-+>p4FhAT!z``0m#Nt5(>WcAd?irhjp=`#|Ft>km$jJN9iDFVYzt&*@N41QkhVOP=Bo!J1qgP zVj5RWn9ZG>ow=c7&gDEuN+Noy{T5%QXi(}8LJQ$h+X~)L0|CDj*~WV0opTF}Nq9#c zBv_Qzu6xZ$%JO-3e4riYVOG)rwl|yV3hQ=Qd0oQbNNZ_niB5>7v3mE2ESiH*S(6Pq z`Jpp!`v%vNS-lP{J9`L_jWr}X&@dy;B2baY4-jHG=z)BW6(@Vn^ky&n%Wkf&1lqMu z>qa~1G$ev5XDfPW{}2sAx zfBm{43zY2Wj`|icfgyeXHoAzjy|RnSgTuBJk)A>~u$;VrtM%wx>GXc0(~@m<4ER69C4o{S5`4gD5ev_VXYUAaO?^!TkwuB8aK(1f*m*a~_79n1LUm^;`rjG}@NR0yi;b_wnb?p6%STrx3j~sQ0cI zYA6J^ebm%DzoAEGgbl$w0hbk_6u@D?4f5zg%O?Uo?zGegmqvYy+_Cm4i_VxeCvpZH z5@tmd7sH`~dabS#V9KDTst;4GHRJK)goBUZZz$ZWFzn_mwCPob@OWZxLRmiLu)eHg z8V2N}Gtrhxbl)NE{)DM_`+R2;j9-`) z^Y;9Uo!7&f-*_SLD5$8M-P~@5Q@zDJ*28#4*iS&@NC-BjQS5%~=ur~L4um5X!viFf z^e`uqEi`R!RObGHfgdo~8W|Z8RyWxxOVyI?Z?Qjl=sb@I>!F!}j2n69orsl{6^B6w zubbK~=nbWiH#tbRJW0s=^Qwg2mXwML#~}>?xCyo+J0soWAcSbGx9)Fw#jbe zQBz#dm4aRS(6NG)<)Ac!R!qZcZb5r{d!O@oC;(zVRgK_kDxvjJPeNkBxbFI}R|0`Yu$y3e_@7mIUH_tVpRJfKFnb^m_b z#2jJw#&RPfSHLs&^u`9s`lGwPA8k|hvhN<_-!3-tZ!f^E^p{C8!R3lR^KOR=<#+Gb zCcV0lXur3(Ih<63$3N+clN0q}8innrKS+MO5I(76Y`kSZ+AlA&vu#ty+=|rEK!jTI`x|*3SD&~A8}1^A8pr>?%ejIyaHk61jV5T1Lz3&{PpWTv=Qz|OBbTu!Rfee zhdlHSS|yP|;Ey9|$X`8t6A&xL?5L@!>AQ~~x4n&ffAhwTH#YfM9wWmd;g)RSXkWA6xpniv(2$An>%Nf@mk=I9S%H`+ zEC}+^i=-qjc%{5TLRieZhKf zHZ(MR5ISORZq8Bc6%j!$BO^odIf)&zA5LUARjxD#21`UyoXU0sj#hhsmcDYYUqy9w zF%*nMxGB+xxP15S{%nhh0#u9)b83z0xw%3h%Y76S(*1PxPEvAm;<#WjYgM6|ysWTr z3k32G(|E+B)t}#|8yXv9;{;5HBru-)V4YGGd-v`o9A*8`Q+;(q{`~o4wLE*0mX2-{ z$;Xc$;ky#Uqcm@@SLkecTimT3_Yfl*>CP7hw00tl6lgm>MSG=L_s-qB-;toE!AwL> z9efYb=4)EoP+jvq2L{v4pU$de^cIVfqBqpb%{6O|U=6x-rRc5L)Tdx1g z)0)eoQ;KJpLfx%gT!k*z_XQb!C($dexI%f+D3lpKPhoX6r&HZa^jK%zEh6&&3 z*qCWewSVktme4=TD}4O;agO5Y)n!vi$9YY5nx~&TS)oMvHDflX{Dz(DG@Y6^YtcEu z`+gs03z;q$uIO&uxRG&e515IJcFr0YH1Yk%-FbAtLh>mO_b<|RI{$=jIQb=5jPX0z zgOGd|3DV{h;Qvb}4qU!+Wg8T~J9qAUwkRdGAB@4zQDx+U{7kVzMA4t@%5|%&lR9|l z(6KXTV#=S&8=x&spdd6~j#0WLLY6*AMO9(ve8<1$sw^KL-`B5SF9D0+k&=>{Fp@`0 z095z^3ci$&WTT7&%1IB?oHfG%*R71+F0l<)7`+>QZpT%Sr+Uy_sAejWqb9Lk+r+ZWsrc1uf3 z>o5*3;W)K~M*B`!p3!d;k(Q>w8G$$xnQvIVcr?^8HMw&(5Rr3rv(4xm+(%w4!v z9|^U*Oj z5@-B(Z%!$2qr9vg^?9;S$_Ektj8k^(P=-@dV&c30#Vu#pYx?@s3BNp4M!+FGJtB(V zp%kV%P{PZ78Fl{v1w}WD5b~NtAjc;B&N{(v=dl;7*&P|iThJYKn6enL4->LKj56vJ z6~%njoq7`*qLaDMN@xWvNU;$MFn5GOl<#WWIs3DNi!dG^Wnmf1Wv)s|O#BYXMpHGS zW>{eJ=eh5-Oy*HO`xM{=?t!OaK3FB7R4rM%iUXElLc@b~TgEAutN3SvnlN!9#kR?B zpU6(#GuX~Viy<&5s2A>Hg32Kh2k9u$RdIrO1700!H2pW6U zdY-H^pT@7d4IADbdOsH@Vvhv_X{rq3STV&`{dX(b3>&M@l3hnoZhHAwLctCa<|?PRp_2`RYy&SPR0 z4WlPsl)ilSOeCJWsPW3FgMCP?kSgt->qN;&NfjWc9Xq)D2p{8^NVv^iEB?F&9lhHy{)d?(cqPol9pDC zCidZDhlwlp&2rw2^6|Q{b@L`kc`@P_BBeXtpPC~1`$zo4E{}M>zfV5)q4o}9=I_@; zu0_7P#r)5&UwB;=4I^^F-`9EV#2@ze5BSI7y?Fk=E;@Jkml+oC?@zkth*$pSPIV9e zk9fdbs~JBV8{7BcIkZnMTRV$9Lft13iXaz?@Ps2kvAHwfQFzHtC@wyJEcG=`2tBD8 zF6{2!uouxc+uJEDvU8co&D|Zvd)s0g@E^L0Chk}S7uJEUQM6FRAS@tByp4_BgQFAh zhulXgoh93g&9Wt;M*RN$w>hHAkCD3f+6gh>l#5iw`Sa(o>a}3HnLip^B64#UJ@<(O zCjq{hQk|~Y00FzNt?dNOM=oRtk@z(wWwq3s*c~sEa<&A*SdT+|uTXOdg%-H;5?UkJ zZ!?{i-DLtfHNo<%C?l_O3P1a!)}jCo&|QsO?jWAg)r@Z3R~UIFQ{TU5BnTM1G#A<~ zoIJ1#LH_phsYSh6#EpWtUc92B;w#kDEhOmtIYTR8ym*lo{>38vm^pvqz^-S{pVy`v zs!>x@zlGx?kXwfg`t75t4L~R2*d-jGB$y3U>Ftmvq?Q3v8Nh5&2%O%%JBDVlw~x$VZH6o6W$ zdAW0#0~(^hsLn*ustT6Tcc7%C?3r7ZPuAXxWVc;VP!M^M1P2jYpr=(00HLOo1_ z8_cGKU0w9Rz=Sjj*@c9J(R(L2$McULPnwyT9o@IHr?2lBDkF)O+)_nF0-9`1vqxWe z-F}KXd{0IuGoN@{8dasUr%w}_pg0897b3^-KQR04B;Y15aG;Hql@*R-W+*@8;E^Ox zfEl0G3~N9^hR^5Ool{~sVnf6P;6xAYihA;PJ5YKk0TffIlCF}LR}iqVLeLBFF9ccd1w=CU#BlIO6HQS@!g@%P0qmM%zg@H%?I~I=x*~u9nAfl8VYoP1tydsKF;oQ81K%H;4BWj zc0zqJX&q{u!&vy1F-q4jydC5+2muvUxKGG|`&u?6wBP?ao>JXJMkk z>LR^TzJs8Kdm2Dwu8%|AxI$Y`kL6GyvS$Vt zo7_6hj&0kFDvyrkGlTICzcMn1?PbKqea}{~eDqwXpb-NE)*;KBm+J z9a6asS%n*K1Wit6V%^Vi0bf9NR8!_pl&_@Lcnl{y-iZ_Xt3}_BT{uxDI4M|6jdqX* zaWawkKU9tLlT<(xyU~R!GBY<<04>POht!@-^h<~gAPDh4O{a#wSYAP}4KCDZJHl12 zt*_6PIu2x6`SYh27TLi;2op9AnDshG992kn-|msAN<|gRGEEl$A|ZHpwicLQ0f9GBQ$Tc2@RY|MT7by??*w|2)U@9MAvwcihK) z+_zlU^|?Nu_xm-@^L(9e{^?n)pq-R;%0hm|c5!c!YTnz-5^!k*0!5NM$Uq*Ja{He@ zo3ymF4Bo4o3Op?;F3zv7PcIuA6BftCkURCFRp#tjafGfQLo{dary0j~NzXF#;_CKu zajl?WQhs%m-nCm&QqFaAh|4P|-~$=Oe~v`B@dX72UJbq$kM<2AsjDXN<$KodrpuQu zN#LzfOJC~#6AE=901>v@hm+W#l+V56SvKXFZRmR`;s5|W`#FpU|asdIE>Qop@=>Q+eNh%`W}isXeJ^8Q_FqGoN3s$R^DuZ z^l*?7I(T_)0OFtj$f{xlr2c?ntQK4uTYVgVQPlJ2kMUAt{fvl+ zR+sf5bf?ayqizvFX9b>pHM$I-&3O>|0hp(AF9cxl7~jS}AmEaM!edCBh|)>spzm4r zd-qiIbJnh1dsa@)1)>9Nf6mDp2=&n~UzT^z<7pVvY|+|?)d0MsgE3~TcjTU?x;iCl zFslIdK4Mb`ctr{Y@SL`e4ja@Hs<|R@>!PHjB$^T7 z!h(YP%u8tGV9c=*;i(WYcyww=mGsx7yT=8-24Mv$_C|!eo`~UHe43{}IiJ{i>Z~F< z?zMozf*Vr*JWoS;Lq<5Szk2y<;rXHZV1&WjerSKhr9>- zgiOOA;5(s8X-9`qT~}8CAkh_d+o_v3BL}EJoU|C2n98~cI+gVGSk8`^`$K_a zguPAq3^J1jk0-e7Ihe@b%~=A#q#c1beZlG=eHWexDyWy>9?<_mgtZBSn4p; z4V2HAj^i?YWKVZ$i3Y_K@MkBK8U~I8uR`p6gbc0;N>dx7RJirX%(fW+YZD>fnNw5uPJZQ3lDCGJ< z{%u7sU5HBVUYJEuUEMaQI?2GpXn*}dQnmm#D@MWp;*LeK48Q;kEw6=`C);*@2Warm z7%YAap8*wNZ$#Ka5I7ou5dp96K5}F`cytT_u2ypPtSBlXJ~Z}$fjiJ|MB{5iQX^EG z_2C125jM*!DHTJ*#+)AI!n{W)F?e84wkO$IyYkcFlBVbD^iFntWglRHXC zfN`I`M{+0jy-k%1{#w-S&c(n2M_KM6x;^wuQOKu#Rw5tCQ})_ z;Y9QXB-f56dIsaUqcfvg8yWal1E5HHn@z>m)fR=vO?DHe9@yxpM&^fe3HFCT2Xzb4 z_@gZU1*y5GRMI(!7ICXZ6}pgkX8lY>TqQvc`@afCbm_k+TR9^FoMh;W`lDa-ny7=Ecbrt>p z*gJ>lJKFHy3Z}{A0wv*cp(^g5R(i}({GZO-hgMxPT<*x`Q%@FF3zrx+31$cWccU)+ zPeaaXFEY%I(5@(D{{N#Z_Z=8aCp{kY6;FWBl?!bAPg6h3ZHg8OLuGVStBu_yQo<`y zly*JtefEV~x`mwRGE{3((C4mqC zuc2HnCSNu3_1IK)^wrcGG`MH9+hp@g(rcAd-o3lr$_B*Zu6zGAaup?te!m~^7j-eO z#LF`hy!PQUpNJfBy~ugpiPO=iNYa#>;16Ai=N<_49S{LP!jhy#019?F+2^(Al-gZI zjtdJDdl(Ee6@XssX5Pf+>HPQ2yT${aK7EWPX(w1#VSmQ|yzBNgYuDzrw&r{{MT4Q6 zjcE5N!w=n@+gUtSVp$}ydxK1Ih6yEn3k>=gfLesS*>Hpmb$(vycU=Mxg5lDdGI za6|}az~}7<2CO_hY+beR5Oc@YSV7!p9I$80PCW1b_funEyx7glyNOZ_rO(K$&Dp(M zfaKjD0Jo4kZDcY(rQeKP^l5B&m!denvuEl;$3;u)*y!jL=v#je48-6G0^#LB3}o^* zl+4W^_6ww|nE=U64H)q;`hLnUNYUwBPrpu24=}lP<=@X`K7QYReiU4-(Lj(n%a2cYK@Ey&_1!{3jOY{*r=@gsh%*~eeIG6&y(px3 zkX@|;|GtVs;Jn(}t#Hk$uBmwp_6fVsQ>;X_#SD9xu(%j&qEL_@`5^Y!*3~7U4gD?9 zgCBrr;3U4{FSCy}a5H3&_!=1dWXj6QLU@tD=R(az03H;m#QErB`ODN)Zy=DLo11q5 zu(z1(-;Vg}{Os8?sad^}cvn1k#+$R#+=mW%>!u>|9R?Blhc`T_?q+y_bYH@HOv#lSS?26T%*KqRD}bQEO6vN{7+rJ;Q_1q?EY*$|QJ z6x8@A6%sJ7)VUv_--NW!yNyKo3|UVHF3Q&Lih zJ{^h41(YmlYti46u#D%gp{2D-S6BCUU!Ml}TU5{OVfz~0qC9|&C{z%n&xVKu<8@BxG)QfPo8kiQ8H6%K zz>mQaqoF@~Tp#!tI$x5J2OHC=XZ_^YUi?=JFgx2E!wuZNq@tp`QBYP^7M4!iN$Lax zTn!CpLP7$8^XjJPYE}~@9%u+bbJK^V!Kz0^Q6MgyDe7I|+c_eF1zbbc zf}(-~$)AV^TBt7NuUt8Uk$rHb4oGH<7_OIqS<&a64!BUVo>3!^UDM=^hephyB0AZ2 zA$scAY|p*BeL2$KzhLnu7J&yJjDA)FphKNz4}J?(>R~kFSb2MZ4uWWf@sl&|Kbd&} z*kfXuE!T)D?sHz=N+JjZ!2=-(g@O+5&E>BMEZ5+zv0=joIw*PIPV*Vy7F5E|GhBQ) zNZopA;G=Fp{jS)eqB9Q5exa$84MM@AM&RaQ@C{L z(KT)<^cjbBYWBjPa6PJJg+91i z{A<=Yt&Lw}4^XEQa$zUT5-u&x8-OMX>o|iEh7439$cORXb)J5vR{)~oj)?(z>3iNc*sj0LSi^aJk z_=T*s4L^SD#098(d?_ecO@T3;7XY&ZmO)~)Nv~dQM7btnIp%16-H1x>%yy=!vCj9| ztGIm6%B!h)04gIW5Q4{X$O8$E4E@R3WW@+MBO|_PC1k;KvSF854AF1fzxntIl0-i@ znRDk{bCet9Y8ru_8?_> z**3XZYK8r$Pqq%VD?g+5;KNgT77{|>F3NrQ1c0PXe1KtT36$2OJrztlnV3xa@C_1& zPzapG+W9WX671tv?2Nny7>juM5qb#CIk?8h2-JW^fKR!=?kG`EN=k}I@JH}IB*##Q zJPz31{eghxWrReFsX+!}aDX^ZctiXF_*{%Z(f;kag*FF8f3>{1ErVL4+&^V(psbv@ zQ32EYjGK*KqXX(i0AI8q{c0W$gX4?; zJ=*f+79iOyqBc)Jy|17cv}U^k6HsW9q|))>_}2I8n(G#YOaG)6#F4WXFFIqY5#n8! zg#{aeJ>ZA==)t01yeNnT6;go8o@B6FckhyokLg%nm3YloA~z+>C6dv^P!m0p*b^_W zl+m5ZKg5Gl6)k^axe!i}%IOpUd;-&gJZv^QSfmgUH+JDxeeyV#EX**eL0+Fhsq(jj z>h0YlD#~KFG|Ty48_SY88OxKJni}~FI06G|OH5g>MpuUGbNu~VJ50oK3$QJC*0GbX zEVjHrL}otsWRMN$VY=jGNR4QeTUlCkLI-EKb;!jo*)5&Z+T&ymR_mQmPnnU zj3+=V<+eTss8s*1rf08$a+!faJik=|@z0gGgV&E9JxYq(8#y*yy5Aj3_Cmh^2A~*d zs24i6GT~jPx}Muy+f|?D=;H=w4e4ttDjjyq^Q`Ehvbu@0Wt?237oH|`8RxtCV{khWH@;xGzUW_fPk6n~+*1XG=xFw)R})oR zLn}9C$Uc{fj^5cN`O@IWLAK?q6U@6EDG+L}QrFUQKupC#atM8vs#Yj1oY1=4(dO*m zdb+m6B?FB5pXvPHGwjP||GWt7$%`9GDNGQP!iPe6$Qs?0Xvk^LQ`?#TUj=!`1xM%m zXjeL;h5q(3V|9Cl!V&wQnp5EwKcD~Sr+cR_-kqJuMOiQU3eH1$z>!)tNbl2iQp9FP zzLhQeSm6hy|B#TNB>%7I$;b!s0{r}N)ZEdm3)w9|m%3o=YI77TU_cgj8$qC+S6TVT zq3cR0b{#5kcy=6_%Rmp}Gkqz`lcPrTd)6v^oi(x&!j0ROfV2ZLMD-dCyd9UK zg@QxfqdwR>IGAC_p&Q)eW!M5$8gQj&>#Ayut zLUdA6!9}jZGBbD(F&^zT1F0;e$4R+N~RUO+qmc-1XNl`|NBH z(5T|dS?3~h@N^O-{Pdy$+)(500`_~%=M2Xx48wkgauH4SkxkLbBG4A6>ym0se78Nm zCGwcE{s+`+1jc|MtLw)6%nT_TK(^b=#3Daj70dT_O0{HF@gi9U4lVT51 z_Jv4MW>nlj)9}xGv!Rd+Mq5sa-UOypgzpOgfrtPQ!ogG$4I|~fP$u|S!f1k4A}B2{ zP8#BXf5%G1Cd7C3#&82CC+0l#ny%lZi_Jz*U-}q9Q6_gJ@xb z;xdHHL5oo^sU(LeiE&6@>(iPD?Ef%t1ps%+(*XWsGRt4Id)o#~(>_uu?;?~HCZ8S9 za^_W6(_s>`2!V_ALP$d~NdE+Lfv_Uz4)QFyA!xnSH8e=^eSi3jv~)f!A9VL%taJAf zk2e|b#Fd$jqhMHDconH0(i`$109_Lx4nm^$+0#Q!#rpFwQu~578lJb;I;YA3(U6JN z`$k5O0IWbNM@>0yJ10m8Sg2m`d+RWGqZU$@uM1O5GWrW8C{dl^kv(y9>lh>2bMQvR z>B>MF-<$Mqg0H}@!9n7DBPk<84VwlqP;#C~_wZ!-j8fUz*_rgOLTk&sBk@p-&E?Ul zc!CfH+ZPR85TMS_*e&k`-@I${H2ot^#kS0`33B=i-^HTkOKx4NwE`VI2qzHGFj&-I z;NtKVzO{v*w#!RO)X|vXFTk^x0UphI@aNATJuGSb2>Y`bB*#xw%F5`!U}&Qb4^}M? zzQD-HDpV2HPG`UGSNZwnqv!pJ z?4pcn*4@+dHrBi*7;V!(!=RK2r$bx>@d3VP3s4YU!+;Oob8t}ad$i=b49K0XUcOuq zA!3<_C00a6b9ZXJdjI|zXrif!K1I+#5H@L|mLA0I#r31&eTFi1`XL}aT;p4A)-`Nh z0uw+A50rxtD8O6_xym0%_s^h2B8&{wK;$M3w^opk0Im>xnq7mQS4|zyfE$`*uwVF1 zCg}K~tG$DJtcO~65Iu6&n7OgBCUjhc<$3k`wU2D1Xt*hcLeMFbZxHC?^BK2S8A3*_ zSAT>uLBrv)cd)Wn>BnSmV#OOC1Z@zAQ0M;=^cOe$Mli7s)oyFO%EfNeJ}h$b49IO3 zIDA+gy_h<}!XThd!Uzt6yTxsr0xcXD6O+#(_7H>?tZmHIPKE^p6k-qj09}6#cinp8 z_vQf%S~W=31qSjJ8Jn0WqZ7D>MdzS74>Bwmf>-j@@VFu(D)k3|kEtVi4}!G5!0!7R z<92b$$rYHYz1}&6QswS<7@PcAgzuujBk|Ah%_%cze*c9m8ua7WP$45S-i1DS5D(oW zElK|!;>X+c^xFtNxX;9RmYau1836&$8GX@fd`%hKqu4(eq@`VwF(BEJZRrQv^xUVL zEu&v{YLUqqvSzoqI$nqSGTz3hcT;zoTCtaMxwQ5U+~K7h=J5hZTG#}V z5F@Oh;0BS%tbX_IIuv^7f}R5(Gwnfn%R(w^%jXx-fEO$=j-z*Ag`wRF3W7fg0;o!POhg=g?4b2IP4sp^m@$#T zgOp3u@rkC`{f`j3z96Uo~{B;`R45#xhDmidsOY)AX<0%S1U67>Q# zrrq%k3IY9I0uBR;jFhG*h4O%GK!d!B(p+7MJ4>{7Ku*+7+MpTv{rk5%tOY={okE@b z!a4eT;0_9ebyS#lK}+yKA}ui?VfUd!w9xXpKn(=E-aK;@U;_bl^z`+kvC&9N@l-Rtb^Tm?i0HNbN`88pAi{EfY&!v%;>@O}6) z0bcoqL?VHfr@g0VEq)t?osVj6#?;5ODrOXViVa;XZp2Cz11;~jx+39{;67Q&$;X#g zsoV}h&J$4S`Op=pP5~+bk90Qnwg*vjgAF-z{``j3D<54J4Y=7L1^fci(q>((drY#Q z0#J+I0m&D&g-@9!f=9d@rCn@bK!c)beOCI(h6LQz zNh>gv#Cjh1U3IJsJ(L_chLPGdP^LQ@Z4GL%1L?0czk+TBy!i!@8)^0l08C9Rc!K<4 zDFpB*&wN0#o|IG_*cytxj)Cno_(P#ujV2H^!N{REs?JHl#x+_#2?-U!?z+!YDB1CQI9GdHwF85Z(wV9FPFd&Uf2VSNKDRJ*;c$U$zMks3VPwoFQd|@E3W;!}D zVh=_Tv@}H6E1}jW)wY$D)s?b$V*?>IFo@ihySyZfHm`VXacn{Y6(SavZO=wf>!6ySFPO}`p18htL zfdy>b(|*SW7eHZXnqP3t?si{-YvumXsMPF=hc}O;x3P9M zKf+?ZEt^!!0Dc6;%K4Kr{IJI%BL-k8Nb7;YJ=`s&yEp!$mPayM0f8Msu~C1dzKL*l zUJLgOC%_As(me%uES3~{&7`P8Q7~;rWp6v}8-C+R%Ni+@L0K@(G z@#DS#{XK2%U(iS4=$_RGFN7*WPoN1Ji@*2gC8!tpunb6tx|@z1$YCfi3V~oTE)k2+ z6&FGj-AH+q&ooS7u!BI>K1?8?)ho#rqvq@pT8YYnln!VBV6H(%QMB;3G+xq#DHfuq zV5*2rTjM3j%t_xDP(5p)F#{)HRbMg5w#9V>bCO8kD}l5UTA0X3q23>{5CQnU6RFfm zeD`Odb!4j3;MskB9oXhOK(PNwNe`70Y-Er!R=^VV$&Vk`7H|Rt#U5>hCJeY|dO{7M zf^kE+_ec2>WwJHL!C_T~-cOMIJH&U>?S>Q^K&Jx%DK%N4WkleIaC9wf+aOpJN5>8b zgFG*g80|wtG>^pX$@A|!z{-ljV6>bVoGU;>kJYs)(fudQ70gsN7%k-dv%_Bs@y1$_ z{^in}JK(e2V8!*aa#BxE@5T4=$;mSi3i4r=Mfup|IpPJ22Xs&|K9~r8v8|ycRUQyJ zX3+c@mCDPFehdB;VJEhF@TI)nXGrLNR7e%FLW<#7&;fB@;PqF@&BIBs5Te0U+Flbq8_~ASpFKZ( z*HthV0toW*f;zgdu6+DL_rrnd|6#UZSG^0|tnJAd7kF7?_jc%XEXI3iC`1wg_BiFO z$J@7Wp&4!a&76ZxjgSsVn+&G`y(HoWvBoJ-ybHod5?vhuqVW#XwaOqEdrDdmGqA;t z8^IgP{BI@-SPQ`L5#EtO;0_u}H`RwIQ4Mz9x((UfqoAOMb)I`TIMzaK`RMH4$8m8S zSgJ|k&k~;_0TLkytDsju%nw#Wok}UY6MGVNImfu_ihn=@;$s)jQQx;vr=zReaAKmU zqGD*z8A&R(D{!tZ5oBnJ-+%o0`^Ihzvsew^-8ZlYa3Kz+Vb!;u9L20(nXseWQ|v-= zv&UFM>PA%l!@;vf(r2~x;W&@zY)NF-svW=+fwuS_%Q6=l2vPP0oR(k0Z_PvCu#k+Z z_LclJse~javi$#BA$}z-Ak@|1+rYX~?1|*1qrlbJtABhe0|WdEs4ZRClmfidz57u1 z61+@KZaJapBq#uYFdML-QEv-1q%JIukBmTKdREJMCbh=DY}{5edai4HI%jfUdN;mR zyWr1@@jwYssn#bnk)%>FIJ17g*ba#4U!#Hvt|ezL;m+$6lrSop7RUcLpmyTSzK_#f z%ZT)ykXsz0sG~L@BX|*Fc3!AxZA$1|!!TB&iTyAfUQ|^@3*(U_0e#c9*f|UbJ9vLf zDf_U9{*VZ%u~10Ki*b!7NOu$pf-;5x&>!Eb{P;m|GV##Mm#G-z=0lta)`G-AK_F}S z)_KziQCm0UT4;32gtrlf1p@p_qn(pgU|?W_`qn$+Q(T;8u#(6Qlr#h{qy3O9m;4GM z&=DLmP$KLhRk$-B3JD`v`$JQ(39>c`Ku{R8(Rtk3%kG$yv$QT%E`;AQ^X2wTJM=_& z&$WbG1Idb%3~n>()q;lHxz@~_Z5y0e4`bG2)?D|gxzPU}a#P4p#32HnXv8pxNd+p- zm+>JPARj7pXaM5B(=f{z$b)vmu77{C@X!G!DpHP5@E z?6OW_i;>;t0Tz%ogMU2(WCPRsv{+|@O_|;@gbpCgHL@`>T@mK?9|7DCE;|=EL3wT1 zCJJ{6X24P;ER!o_kfFee8G;e<#xgNZeOM=k(g5^a;zdIG$i%JSRM-~2D&(@J?W zHNXP&$TFRxZFza8Fe8}X*vN=FUka@*-~C_W28$tHnBUtAvz(Q{UG0HdBK8A3EC^`9 zWFg@UvFdPo%w{|&h1*-VZ(jq+D^e8h)nId$V*euItkH02aIgkK#}Ssu02g=g@Pt|Z z4Z$4lA&_&9N!5#{wi)T?MTWTxwf;pkwW#d2qfjRwj}8p%rY_HNV~zhj zVg{MVB3%}`e2P5;X?Sc<7ZNQ4dfkBYI2T80VA^>>4CpBl)Fa&xoDMuAh@jF>7)9Re zj_dn^iXR_%-Mj9mO?WV4fYrEWdcD`2n0*9NB;$7DVgP;bnU)D-O` z7!}rsIv(b2fHH#sj$rdain70!#;g_(J;a%2)IQMN=>a8K`M!ZUcrQ_wg$#gm4kdr}#^>3D3~n3&UFm z9fBsh38+eRJ<|HUtICQS@t?|IvVQ=rCfKAZtPcg2#ilBSMcn#zKMxxm{h0V-+UJyg zweJ2JNnaLmafw*>$Gi7GW@kTh>GhJh_+@{N4GJ%0d|N{uS?+8P zJYgb*qbVOl=(87bofz(1LL`T3=(vX!1$>EM{iy&K?f@`cz&&8EH|ey=Cm| zr+TN62RFc;|Dq_D@NnIa_gIMIk@A=Ci$si8!Dw9>b~> zj59w)^-A;vUB)NCXW+cSUG{)DoR9>FN$R!@YjBbeH-{}L1lrmx6QvH$sf00N8i@*bmQ?HC;7_Oh_FvZ{e#03RWLAb^}r z0+<030ODsNTSYd-#!4RU+daGgsSMTEa1C z?rQkU4haqA-dWNu2?)d>juVd~%~qvkl{3inmhDdT@`;y0&%4D~#}Sd=zkY4!V@Zd* zA9BFnk^82*IXH;*#B230EAfSpW_sXk_w5{UW+Tn%v17!A5D(B8Qf`NaBWHTh2*(4y z;FuSG-k&|w;ja0q4=E7OpyTXlzW+JZ%hrs0K)(U#9;CfesLgD0)hO~k2p7hU6>hP0+CyNj*1CWuw zCkI@FFp~nQTQsDCK*dAQxII@$d|qBxiwU+0JK_jyeB1a-~9stGkI24i-4b6-EAT zDoxv07vv!SJP>f+<`U(ywh7J8gjAknH~rSuR$}J~cZ=%R8j|P|DuJY&ZrYf>9MDI* zY119hAK+t%r8gSha;&h8b0(0DBbd5RM5#OEkG2q^aM zeJ5fRUI`{|z{9u>?NJT$Agl^Zze}xbhLq>fp+kNT7#epa=&h@TmJvZ^57lEY7I5k@ zLgx*0P-=EyXr;plN@{dH(MoNdcTmQn^dzUv-CvwDB^(b}>WdFq&a}dF4JTkR2ftZv zc%{4*ZymmH6HZsqiNQCTE$-m3!&sX9l>-Oc#;iOFebE#Uzdgt`I)F~VS;Ps-iSrkj zwr`K!gMaNSl0wDb*Or@mu@%EN+$ju`qoZu>?9b0n1r^rTD%zy2i29}tp=(a5>E~)w zG(x5ean|~ z{S6htyB9t?a#bo$0WQD*q@}^im*Y?p;-iPt^w!Dq9YvP4?28Q|*gjxEV#tX@_oSuc z)8=*umBX%d3kLiMzzLHiaxih|UTWvzBhF)E#}hAj0|f_!j6%a*r#v&uSj4$#ikeICTk_)yNwV*vlpziGoO zmkr|~_5dy4>Ngz)f$FA`+=B;zd(+g#Q`yqod=~zdJUkWZA5gpiKF-IelPsz;oRbSh zYr)==NM1<4WRM2*_6jJ!$RJh+2g9-;id9GzItK?gYPUU6y1n|#vjyry*`HAvWZ|@L zMo(wd1Y|UK)P@-DfvyJn$N`94g6@gCyTA;`wVT|Rx1;|6(Ifw|er+v-I}v2K(q2LU z1HaklK}TXahP4RLdm`nA8dBpt?gm!aN?j{4FqO zNin$*x$Id=#&S@SR7L4yd3J(|1Yk*Nlzo-7rD{tf*C>`oLj67DqBDr7a6hmg<>z<8 z8=!+a3vi7;_`Vf+}FQTed?a!vBw~*0oVi7ru=|I$WJqW_Rp2u1bpQ{2}l&F--f{#X!^TQn^ z$_Kj#58iUan``%h18(32YvI9whk4)vr|q^`{0ccZ0{l9$TPB8rNG{vr6_iy~-@@w} zoZWwpRK&E(Gc<-*k`%Ez0|1;wDI}7ks8Ra{T%;A;A&o~)B%C0*$z;5@w|8Y_Hm(Ch z32xB-l7mHB?UrpLY^Rhd#55aEn;c$@;+?)>Rgl+La!3Kf{s?mFrTB}?pBNi$t^s*MRGpbA7@KE0tWzRXnL4ADro2rk#kAlvSNW##0r`B zls~UpcD{woi1kiq{`!>%%ElUqZK1{m-1y{+j_;N^2Am0pj6#kZzZ(+5)k=b^g@NTd*41M#J5^N8K^Ux>b05kTU4%;!k$+)wpkrX5 z9I*^Xb=`%fv1SNye1#J{Q1L3*9p*(zIFOk{q4F~wt z5g52$^}Djg+X3CM08Sa(AhW7Wky*bFr$iM&vxolSW<*Ga8t#0@xj1w_9ZhdvD}`iq z?Ta~E_epSM*4t-@r^Co>ZhVn0@|?rQ|^5G6nf8|!Bk=w{B)eT*}Gr zSq^y!Vskwn59d9rWOCsJosw-6D&&XwaXhuoKR+dZ^Ut3ZNw!u)$ec+{tI2OHb1N_% zByo+6?NZBS>-h1P7j*iA@T&!4Uj#og{ri`r{sI+$`s^NY%ccg9`uyKNGsQka;eS)} zzyDg^sSvM-NBLiWI#?z9ADjmd@Lzuxw9bZC7TZf*&r6!(=Z`U5G15Ez_5}akYe!Tk z+x9HwNgSOpPc;xo3K&b9GF0#hCcieO$ht7_VPC|qsSAUjlZV=_W-@$^`N^Knxopdl z{>lGOH~D;TZ_bR`EK`e1)@I zg`j1L@+IYo!gw_UsU{tnvP#%UY83` zz0J?KF+#27>cU&9mD6&6UNk&)sMmKb*y?q&x0glbdt?24S|+C)f4%KZo|j^p%T}lC z!lXxBn2Zd+yLM#jJvEH5ThJfflM%#A(%zJB* z27RG~-8>o|=4id2JNev4YbSghqo`QGTFH1HKZ{7eNRNGDCtWM58rDYTe+@X^U|1;E zqOY@96m)vmOmN;S!MTSfkMmw#uH<>>SNAdK(oZ4z_+jl3k1(g^ukWd4#!O~Sy7iuW z>&F~F#1!PLuQNSmtS7QS`ElYXm3QEm7tM2i*>$T!yn`i^S@I`uygV-E68WL2W^}P$ z?fNp;iS^SX8~detvj(!>Ol|!$xU@MdFKkDr82jN{A{5KS^#IJ zIo@U;nBy@&t}#lcc}iFR2d8a!;@cN5uzvk|yh})$NLZtRtcdA zgJJJ-n8%zgMB8gNFD*Pg%5dqJZz$JD-*NjpTD`wL|pLh@`XfcW?W; zcYH}7W&itQ0|f$xJcVV2FBO(KUBXi@$N9fty33dOrtnKH8(+McNzcpD)y^KAb2DZe z-qwt0e{(Vu$l1;+FUQLW9$<0X?Rc&3!E=6_1qv$*^6TieZr|C@60z3IizY8wS-NIV zs-nN&`p4p-TsK|!I6If6AK0rVls9|3w$#i0G>4x?uTo@ATiCC>W5YgX)BNZ1ji5YByZ~? z=;H_81qIZ%c>GqiYI=EaK$Pv^(Xd~%$5zUR1y#hd_H4nIbYkH8@qWH$sb$zmzqvBX zjuPT&73qGkHRek-*YO#p1vtmd14vNTxzN^}?cdyW?Vd$L+~kX@QSG1g+S#zXJ}Y7n z@%3VFn*O_;$7tJ7{Eo|w@7&hg zOBwl9b7{`joKe7JyVK9U!JRE(h$|z5%TvD0^rft|^X!VxY9AC>OO2a!`0;J)y=)j#Us6_fwp3Zck8KU7)O!ym>l}Wt zAwQ#di`^)lODpSzimAod#$)30FB6%@He9FIlS(<<+gNny#6;_EX9KU(8XC9jwX3ehfY4+Zrs;HI;!vc|j z$*i1f)zTBALlepmH_AvKW8bv!HI4RWk5k*9&NkEiiJ8lLk8uT7nlucQbcsAEx{#>( ztFhdE^!SH~MLq6tk)1hvSP;CvJ`>)bJXA1H7}j{E&G6!{#`nyYT%&`#m>iSi#ai{P z{aB1VSJlo}>r~3knC%kpSrp#&>^n6+ZsDV-90Jj%3j?zA!3Rf&r$ipB$Qu8!)N8hx zD2kW5{@gF<<-m?DId&&c<~F-~#)~O6@Z4$(J-PGE=%({b!Z8R1G2=H1^1cLUG-+{h zeeEn6>@}?{uh{m^(uA+_5f4{oReM*SQP`Z#%9El^R}zw>xc7sgwrsVdoP7O#_N6MxT{h;FO)ET&Qt0>Ih&eD>crBR0-6j6f zZ>^@^xnsKmy$r~nf7EBo@PTU=^*SZLvXX6Hc7kp_ojnSfZN~-sw>&irljQLGW;KR4 zIB`zBE!Cgm-em9GbLfOuSi$_p*-74?Y3+kn$;|8NX}|S*9->;h zzb9I(va{>?=tdRu`hLJbk(yDzY&(BAXA@6OJkf%^u4APMWn?Ynq>C zrua2kukhWcT+xC?br~zzFf+EM7q-#Vo7(bsHwha9>4R*7S4XEw%*`n5` z-F?{m>+7S9bA60Q|K!jzH;__`Hh=51(7{9dBEHUNj#Aa+q-ST{=Bkjgv)Ao3E9o-k z9=v`(rEP<~u=Ul>wjs;xrYR|dxTrfHb7o8*dI^8D+m_nYFT;YAI5yW>T7_mA9Zl)d>V)=${j zWM4&b1?RC*Q62NtCw(Zclwy4yd$fAgy9ZsJ91iA$N9KQ3JLB-hukct=;HH!pF1m&y z-&0y~4V#=|kKpC9(%CL?FP=@53~<~H7YawWSPl* zPga&&cGq$KrACjuN>2H^o<6FzUL7)<4&If!H_cMoa`NR0s(JkrOJ5{M2NrhmXE97Y zoFoxv^ZYx@+;sglC?GC^G9Fd~C+EEkscQ?U>@lgUnW$jJng*x;;fXU{3SZSC7K{ zTJdnvm_n=0Z|pm*bJw0`{<%^_EvrBOLL$4s+>Wesd?gjz-XGDSUCW}q_}E2Tn3|u# zO!QG5D-N`BcS(AYdisvPUo%7TyC5!x6ESXI&J(4(ys?Fm5?D1qy+Z27tp)hSxvl~teN_S#% zGTt4?C|wHq=4Um(<;)2N)SHDzyO&DCubr@#H~h8wma)LDdq+^GHayTfnA(;(zT3(s z1LY9Yu3!O=NNeHIVvmQnilrGRj$H9G_*V-M&t=*|=dEBquF#QXK6tD#cRbuI@aY99 z&k)nslN%2Ij(qdZ;3IA4{+1U~o^kcTflFl<+?)oPk6F<%Sx-}BL$5c}(3S}ZbDnCvPgefI( zb5)if{mX0^C~VANSrYOzqDiF~`)PUJ;1p)tV82*v)wjTVOvyKLYMM9d`<1W{ce)3; zmXcq;PN~+oa_yS?EH`3r)%M}d=A*m!&7LUfy0fkK&LtmT?zm%JoLXa9Tt)~b4ZfL1 z{JOU6xP2;hCrb)b5)xCt`QH z$6QUdE95=)qVDO6j8O z1CeM4-izchzWiG}ta-9r-es(Ja-l@lZL^*AGa;YQZSKJ}r{XW%v#9@m&d+lBsNF-c z&^qC0Z8z!_LkVW*9`a&+e`+|w;b%0=amG^ly`bK~GE}t>`XhqNo_6HMDXwasG39HY zw|l<(}9;h9zpHt3O5u+A2Q(Mis z!>e;-FnZ&)E3?#miv1thSYrS5>}{?!6Z|xA`S{%uvD;~{&7=FCOdrqH6I#q|Xb~^* zpMP+rlS`P*t(vvRcryNskkzhL@5&Fc98DqZCW|xY>)I^O54Ov#Je5T)L9d>Dw0K9A z;`6;Ro#VvlC86Bg#nPHXS8MlPcmB>(GBeNCfWP=j`{&W_C$zagM}4n-+}SppG11dx z{nK|t_}1%A%gs%N)vUd~o0+BB48628hF5+*WUKaW)^g+6_sSaxPv3n@&w1<+mON^Z zbM52zI^{OSz#6WK+qRpwYegrO+zRkFJaH3I^9qeL%H9j1iSDHrpLCS0J9Pi{5a+v) z2?lW|<{fXfkoW3~oKaI}L@aeQejoc`G2^@4S}8Y}lc%O*sbX4tNIs)ri@9fHq&7Pa9L8UA+`MHW_ z&_r%x<4EOlJCPpxQq1oBa4M~9xO@IEt;Auzj7g3EL_xDKgRgfAojZRfty9nTxPX2p z+KeY`x6gx4?sctyJhg^6EW~Q#PtESQ6Kgcmvf{y_1@)1pNlA_%6O#e{yy;h)Yj?V@ z4_3Pv({5O+J=3(U`__GpS>atb4~O`$R)%hq`wyfDjs;N?1>?3CoUY7OWBMsS1C%3 ztwCSpTaIuTcDAp3EPhq(xY?0|IbjK3#kz&x(cHA~Q*F9>|8CWR@HW;-(d33Z<~LQc z$Jo+83@i_p=WhR-^G6(IQ+ditclR|igs)9qGVyz#eP;#W3wCY6ZMXLN84s{Wg|qLl zwAgAyza(Cr;Ck|7(C?VsOT`7DF9ZD6p|99>Cyw!g(pyP8xA8YwbK`e$^(EPMp)Uu- zVhxs!icF7NchHMCD!Lc>0a&ol8+`DG`RC)f_a%FUSp%LAKG18nEoAx`-XaD}XzWLq z?ljA}f=7|(K0I725!2q9)@DIxbwOmfmT$GG5gQ2^9nIWytBw6M-`gdP9nqZAj83{H zWbMODKiXjMK0u4x>ko6w0nyXSKTgEFeqCeP6owYjeEOACwf5N$W+5M~8x%fH@2B+B zgq$sSbhBXWdx8vB3h%?CQNTJ*vo3l*S(O{b#ryolZg0ox7<-*jWk3@tOYfdwAK{C= ze`B^Hq=Vf?Xd?A;(KcMVkzs2vzUi8G!W(YR&zgh_qGkCpe?(kE!wE>(B+bqKu!dec zEq;<3nsj_h&34?0k9n6yFU?w$mr7@Cb~9j1g$4aDH~L?c$$|c_si_!`WM(Aq78X6< ze7yV`L-1p%>!)T~O@T`|TyTz!Vd58XI!^PgtkeNTTH!?D>CBakitUAvDd-4o8?XW$oDBg%ZLM8>uE`;_5k!Fy=VO?2nmgx~eo+Ud@l zpB}s^hZNS|af<&>OV{^|?HyZava+^duZNEvz1r}XeQ7yjmiyXxsvxsg{G#1a3F|}j ztKVq;dCE+$Q7zWZr>IhGoOg#RgGKW{V*ca9P5pYY+PycAY*6#ggrIT+CsIIeG9H#UJUhM3bBYEx;mI!0+ z@%+6f(co7g6Q-FPA70aU4)5R5nk^v8yzW`gGwByUf72e%QQy`ieXO{-Y{ziMr`MB$ zw&$PnS$YRvC+UMUgJ*vBAz-XqPN~|nta~6JE0)GKkflA(Em)8FhIhwfwO7}(6Iyg{ zIrT}${&sgt+EU$l1`D_h5teQ>4SLi**}L3c3I^A^78+{zf4wM;b!8rULy%!|`eMq% zFOp}ePL^e*#z((PktkQ9mw$WxCMB%@Xnb++$E=C`T^DVq7^zmGP5w#Q$D-T&}bmj&?od@V!hUJbGw^b)nIS1D@)xzx%b`_J{WQ; z+29bJ-RSNnDZ!$=)-}SBAL{g`wGI0`1A@~mEEp4xX|wkR=Eyd-l>e}rtL=1e>0p%8 z>b`ftcipl35Br+5>k9YlGiwX#g&Yrm^9`WOZ0R+F;e{3PLKVM14N@g@+I`7MY(Z|6 z(9!aibD`6$TKLrNCK~*vEB@rK3HnsshWOxvM!>Z;4eK=A9(XAe8~Q##;peBKw2J}` zmX={VYqpBmt>UEjyxU0`YV0b?kKbz7zS}sqEK09nY0|qnFv)!b)uIM3!#9nRTgI=J zLoVJk&{-8&-8tS8Hrr3b%Wb#LMa46r$!^!T;)kmyGP}R?-e_)KIMN$X6$@G`$x*8}u}*5hYE5w3hk=%c2^DGeS7!R zI(^P>`QB5*552Pj^t+e7Ns4>7H~)BdEnaapVOqyl(86HLhS)Wnq6{xv#H-YtOct-c z3m)69e!P{)CRmQeRrcwD@wqcbAB&;qFEC8@jDvpdd0&HFyzs&jortO_y_gI8=){|8 z&lHrf-ctE-C;b;{w@{<%i9fu@$?I*yEEj}(@ey)4wI0eig}7I%(H2Yz`_|1I#wjYT#t4f?*NpOx`(Jml0ei>JYN z%pII*(x=B=4Xg5Q=rq>Nd$2Pc%&E(%#)a``*-gRa^qF30OpKQGuXkw=#e##hiuYK9%$oaU9(|mI- ztvx>6ZVk_FDm?iAUmoHR(iE zPG4Tm)#&T099JD))SW|zuK62c@w8XGAzoo;YJKGzKHT}sA=w4}OD+9NAr;uU-(&3y zyJH^nL6#6fGga*AX#^C&pL*GJbD`V|$*U}NN@QElDiInekB*UYa9yj}2UU&f|6-=x zm-DE*?hQXE8>>w-G6vm4mgbUTSKP@2gRSJh$sc>ps9M*NhQIXG=nuNpI#W;nxrhQk ziAi&z6%zfX|0A=sz-f8vf2O0(BrW@K<<;6z?c1lv*d=3jVKvqLq25Es#|yjeWe((; z?Y%BqTFJ-rvc;=k1j5~1%WZdJ({y|eIq8(v|5>N#y*zC?%Bl`H7_j`1n91mYvHckZ zH;=cn(CQubJ@U;bG7W1yb&rxQ(}YBheUltzv(Tw zBPqLrn=f5+ReS42SjFfd*oV~B{N3%6DC=76*lST)$=5ZV`}*%*mhzI^y0 zXHjr`eL`W)k9cB(U5%0W40eyiSaq`JcuGNo+q+N|f)0eDgQ3_5@y5M6 z4`mFKg?G_WsCig8L{r%8IaQ)>eDL{kO>t+mG#Z8qxWF@)&D=NHZ19_i>EZPa(^joP&-eCKeXLaZsNo#1 zC*eBsPQE27;<15n)IBZFK#%Lz-M42`c7K0iB}3o*tv$@%^7Dg-t*%ru(?{-HJovya zYkiVuwA=Df<_f8=pYvV3j8{zIrmxapZ4Zaeod33Xz1sDeuaR6+O3pRM7n8ZkpBFm@ z>$*2x=21*Kckx~hHKedDOJ2ci9AHMzi&g4w*j(m5epy7y@@dMq0 z@e%lMh5EO3#`lQa8c;3yHF~~md#oQt)AD%LXBSG2l+y);&b)s@Z4(cO(@?Jaim)Hw zdAw|iJ1Uctx;3IO+l2dr@vwT=vF1zD`=0zp6?Dz!E7z-Ud+&W{z!!S-U{Ly9<%g2< z>o0tbQqlB6j(tGDCi^$_rOpL0e3qI3jaN{;d4hU$lS|z?ZTGpj;%B-y)GQkB8BHOh zCbM7vezsCfFnRdC3~A6w)NM+_c4{H+=@;7X)cZ@>D4VWM=qHuB-6uMo`B&IZg%xAj za8qrtdG5A9l$rbPo}q8zM?MsL?uM<>&jyKKAN5Y>T>F)FKkn}7lY~Cd3)5Zi$F~RGxZb@Kmu2H4WuXoLtob zVYP?d%r`tZ`%}p#SUQIdO$Ma>^k#aWJBIZ8ruX}FS-x-3+BnO67Wx92&F&j$Kwhr? zQq7qlgz|hpZZw76f~$(fh1Cz@p9auDF|={naOwH0XIGXzOu9=niZCUwA`Y=~!*ZEC z`jW>AEhHU==QSdqghsvQQC0fL)FbRJ9AfzR)1$LLXxH}BqH*>8KXhyFF}Mfm^^_@` zi}n{1w)m>`GGqBJ<^}G^w1q0|7&f~;>Q{(hpk%B>4beT<^N*|k?)>yN87Io%;ku<0 z&w4kvmrAY%^&BsKfdKfvA&TO+RvaUZlIiI8vrX?#e6!Q@>r5I-rr#Dbk(Oci0Cp^#0Mwx_btw-g{!9?30n{%~3Q^9zC(ZoD2<`PUNbLP*e)y=xRN ziW+!7p5hVY-9e^Y=p1)FsPEb8$EX6)$#U=d+GBI0=^Kx)1ZtE#ppspwR@mrSybIdr zd-tskrQ-3`nU*|POUS7n%^usSU3@y;E;Oj;oz-izfV{b^h| zn;(`RNM9cnq8@1|zV!W2(Z@cok7p`ybUE~Y-8weQrm)WbiRi~;tb;Br!B+QZ!Bh40 zU*kfL&97w0+FtpTY0!6lruEmXfy1^VQOW8uyCT$zJbat-Xhv2l)Q+}WDoresKVG%k zw)WLfmel66$Qt*1gESjO)0MGpZ6|yl8%X*z<;6G6K2@#Bj} z(V@@5b-gjmwfWa?{ED4jUZd@uT)K}I9A*-_iwhNNJ&%2Gz>}L@uwo~DQ2I84ppKfA~jd@BH>W;ud0U3zO7Df zyHQV6b!T!L>qTF`ymor_!VTK%)_O!QuXWv(JnG4jRh_t`X9wbs#FxEH(&H9S8Z9V1 z+F^CZLGIAb(wGXLsVmLK9ce17cFNBqKfhj{wwe>T^M$tWlXrkb@#d^Di6>)~Zco*w z602NgSn?9Dx~FE?YA3(^!ClKxw4@NXY9%OIJf3jq{oW%#K4~0_V|Kr~8$YlLT{$8~ z9WD`65ce@1=nwpIMlM!-=OF9n``=br&mLl}O>N|98hmY_)#9*{q%OiP9$mCrlc*kj z&ux%ZI3~CwqKpG2$p!_(MB8v+(0*gm-D|{df+Vk`R9ca4 zs{7j%dTfj$1B{xYkNwwwZ>8*G^HPvCh3+vL)tqwL@oK^UY#?_>zb6YhRkF%ccq+#+ z?rmwyjO2f89-591gz2R3`O;f>|3+&W8Hd!2#3}K{=234arQcdwEqh-&TykNTXjt5g z01T1OkG$1|==gYc4)f35{%gKWH7{$FY2(+uGNR!h3#jy2@=k8;{}d=!mT+ znY&re3)J_IA*LcksCB$?u7( zZJxHmVuob6O)Rue0zZCyTu|n=mhHqL&Kvs9+T23SO6*$Hc07-m*L{Cox8p%%51Uv}_Fki<-4*6jg7H4qEN!Wjt~WQMOf)bHgmHu5GO?kY-?C&sH%=ys2kWnK=@Xv&{b_IU@GdUhb#vp`I_qH7<;PPH%Xz z|HNXqdJhVfm#ee9^e^KS4et4!IrIVpdv`KKB33S+krrPi!=e~@;Qc!K*5u=7%+$gf zi|*I#W8A2)Xaldk4v+c3zre~@BfmJajg$zCYiG#66KugB$Iw zq8v;hUC<^}*;u%kNd^SKMOG5R{>EWbVmZ~wCDPPeo4i4Qu(WAyIijR`*~Bo{B6jDAo2 zT^9A45`s4Aa&K8fd|xB?+}Q((cYw6iqdRPqgXdiTm6|clrGTqOZ{1I>AQ}B zxp#eS)jlRMl7aMu>a@p)=V|MO`6#z9RQy$s|2Yd#=)Q2%-EgI$t~%&(fwKN?G+wR@ zjmY(SFH6i6(m&0)b}efq$}^_#vhaoEVYAA<8yAkbU=NYAge?3xIxHvhAk<|x@_5D* zDd1Dq?2|r`D{OMDTdYXPsvE9XmbSaP5}5J%t)oHqW-U4%(v4uNmknW?ag5lRO)1%$ zWY`|tS8HW=?T%Mo#LfqyKW7co)*Eb2$=Pm-SE$xK{Ah~WIrSOD_HJEPUYiLEu`5L3 z&MD68d&KAr*VW(W9|b?!bVv5ATV&|fvu;eL#KtLi>r_=2qZSj0LnH zyg%lT-Rt!RbB2wo$!p@=j5n`jyj`2WECsQs|=-qktcVt^aUL!{m56z41Up*5~ZOuvZ zy5;D?Pg0Rbu@5q1#C|Bfy9Qi4{4HrS;{~Mp(0awtml!5S^mW&^Afx8~?)O{COs+@0 zF0e4@WKci#FzwKg!}*v!n06t$$jWNlOpgr9<$e%TLVfnNl)j9H-{SaL^uC&yb~2RO zvH6+P{iv2Y)h(9s_~6j`|7gZi#AKK_V?M8;JzggHPp99zotypo*yTsLjh8OhC8Z50 zqbjvL;w03yS)FyUf78p1)w|je(nt9ISJxH`{reT_v3a)o$tV1BhfcmcjJ~04#EjM+ zpQw( zzI0Qhx|+LdG36xm3hhIN$gMa@;eH;;9LFbfJ}hsf|Ir&@^XyCM-Gt_?*Ke>xR|y=J zx_I-X!TERXMx_Zy1u5mWqQ}Vd^IJuo(^!B{+8(}>IQr_KbZmAzCbES%eoY79^Jx@rCSw(9Czxnpa}LZ+kNe6Cl$ zxoe}BxT>1OeYNMNgeCR0BRO*~z4grk(9)e`;}2Qtdw6D|ko;EO&(zSBuEfnLpPpVKVgX#FtGrU$$Q{-|Eo6Gh*E8#+@61Nks))KQ^d$ALHa8 zKl0i$d5_NA;dfvAI`418%y-fcbWky_G|*{wnDjpz$t;BzPe7MOmm=x#akk6Cm{7YH z!~4$CU;FGH91{nh3w~;pOFC462G`|l$53N@=_))w{0OfL{pOfuPQ59Q?k&>;v2Rr# zsaK7a0zXwbJCDhT2h>~du;@7y;(I6fGTMwHkN$dPPi&6|gn;*pP&9epCmlW#)ui?N z%>BQo1Y%B(ahO;8GTvMxVR9M+MK-lM+zMBom%mV;!l)bs^@Au)UA{Zn+N`@Wsl~5B z57~>i6VMzyw{z!xhp8XyIXC-^)%C~O%gZ>78SWoQ7rE_o!dUKvX5a>~b4*;+HwySH zg7^EooH!-Goc->>yNB=6h17p_iwY@L++o>m@>G{AXVWGoIfn43cLXL^S1ZgsUPc;d zZfscoQ1$z=`KOrQpSpfMK6c#vioKK--E7Zs1yuvKu_+7r*;3tstq+uLJr1Yk6HFJ&x>2uvczhtJwVr3- z!)hQqFZs{U( zIP=H`+(1y-k}kSV%jb<-})*l?~X;OJi@ppg+RtlD{j%Z)1}4_!f(AY?5CLh#!m;ba3j-KPq9j@%th@@snn|Z=OhBS3P)sPVv`bu4colv6e2{Sl=Uk zz8p7vcZ%fp`lt`bHHqD8b3reD#pTVRk;5)x9_udDfiyG5ZCz~KhkCdFG2dYEG}+sb z=Ek>{AIYC(s_FL6$Xf)_8TVRK1+%7Y3AK{g5s6+~Pq^csiYI;a9DLb~R71=QgI!jC zw7MK3BOd$9?ArA ze0<7Q)DZA)h>ic=^y*bFs;OOiK`beL! z7& z@m%8Yjrq#V!MDw#-;et^)tRKs*g1?*>o5E|vTriz?uffk@PzB2ZKZM4TIPcX?|*fM zZod`jz-V>O?~NhkIbY!YvSY&Qkqe{GijCjd+mDJQzDctORc1K)_wGzmC};IQ zc)X)XFzdX{P(edqsK)79Q$IC+i_x*F4o~i%+^n~Yo~Lvaf5_3hbg7f>(NyU|l}TM- zkiCP!(HUDK??;a$9M{C3%szQOwLz6EOweR{IgnR*0UA-B1${c%p#AbYK@#7~?@~sk zp>aYl*JclXa?^3pDoTAReX;A0@9MMlc!qD&zs|oCjQ4MOvB~1N2s2yl$EvT_Pi__M z-f^*EuIY@)CXJodw;iJ-8>KEtEH52V6`Q#Ehs zXJs|Flo=gKYf}izUjMd2Z~R$2b$1~9@Hd0K*9$zB$a|YTvVJTr#@`J2XgtxjbJW~~ zbN5k0UE5~YyDh6O+T*2r9oAcT6*oD0g~n~3Jzl`4?`&h-zIl()yZ*|e#;s*;T(Wns zY>UZ`&ub?$4Q}TdQj<^Vhud({%>=0q4Z{o8(;5s zCT5Fw{%Txls!J5lh#S=(|E79u$D!4m41vF|4;;<=spI|d>2Aukpo#R&_Hj9Bi3-mA zk>6#?&%E~24evW^yx2?6cIk+S?m(W@L_@^l@F~_Ub2TGXVOFX)9eK~c}1XX_4IGbg?#_CDL(@@<|A z&)_J9=da4Xq1bBzO-I&qqLbP)_GeIp4i>qcDA>_=h(6+wyh0mO!^aHuh3P$?vYzZM z4k{GGX09wA?so|}xOd<%R_Yz?*AL#8dTi0TxlU=Y{%1>Lr@A!!r)sh)D4&q-4hQQl zo;kO$qULn9mx}4i*VI?~r*+s%qSv}f47|}USH-t!yKhMNcFN=B>yE_KxDPa*(ROt? z36)2jSu)GS1W$CQmbAaTt~VP|86jXqIk^7y_Z)Y}kWBMrMA^5G;_EMOJTYw&R(1`$ z)xc0bK^RChM(M5*38aT=e~a~aj(FoN=SLJ%INC4=)Abhevnqk?N4T>cHAi)HQMFE z`9Hd1OmDr8Wz+O8Z-BQ}dj@XLn8d+zGb3c0WhIedHrr6$z3F(7l(J}<35PLe)2!3p z^b+Q8ipg@XjvRp7zD)#q!nXnPzkZJ{6@NWS&BO$r{8offeUC2w#suBXp}N?0@>ebj zlt35!^(QALtG&{%?n>Uyhn5KFb@ zdGi*DCyyT!=E%vT@ZSH`WgcJR>u=Z#pAf>&+{X--walVcn&ceC5e$UDk}0Yn#1ePQO|AQ-~+#?MV6;&>;NaijMaMN zFtaIbd2Amy9rIxlOh4$@YWVX2$}4#LR$<>Z(ZHG7kllVD*W%*|4-1goWy?HPvq6l) z&t8*i6J5*A6(KC33Fmqk-B_vWft+LpXW3nK_4VVdJf^`VyevZr*I|SJY{;FWA_+La z9fpqq;l^K6Lt*4T7bV|4{G#)vUj7zXS@@);^1`+;4F0UZoY9O=^_9^BvZS1R{-}h6 z2^?{$HR=f?#`1Dm0?mP!t_id-kSyuve&99drc6C?xM&h)jxhAAEP_!n!B_^%>$WBz z!9s)UTOf>CF2Q7o06~J~YHVj0hL_#7W9sI?qJ(F}PMC?^#bv+_$sRUi#(f0N8*o@O zIspY7Zr749onR-poa;-SWp~BkCaG<_`rD=@*RmB%7aDNFh)V@$g?f~6+qQlf(FZ7Q zfL~08Zq5eSbX2;)%<*Hq3_Hw(2-igX7(nL)GXxJFtbS!y-vne1zAcP;4itw8z{Cj- zVfR#$;e|>#4dSK}o(yo?+670tyI^Z8h3%nB7|VT6;EP>cLjo`8r@&DA2L@Jx8qxnZ-kcyS!1iM6Ok0OEfBIfCn`Joaz=Qc<+c4}g$zaz2 zIt~Fi2EK-czzf4NzVhQoTBv-Lr01}9g>i(}8E$Xz5@4^K4NnN;9=K6#s{Q!D-4` z%C8Hi9k{PdbtPb@%+Ai*k9QnAT=Ti7d_ND5pXTc8{Cpm*w#ZMg@&W-7SZo+uCga`z z7MK}e|fo<>G8!7>HLru*=zFkj!r!qPHO<(CSB z6Zph@C@=Q{QV~|z5!|Xz`};55uOE`9jp_-78w;!>4or;0CvF5jt4z|A8#msAf#TOv z_gE~5QS67v`}gGm6TW=uk}OR0@Uvi4%Bch#$0rygqzmkZM}_;sfFCH4vUuVN@L)KQ zd%H3J)cWd_=P0~aHMO;s5LjUHv$qIFGz<(w-@o6(bA@U1ZCD|WjiYMUU zuFim+901me1*b7$(8#<=0AVg)y(-Y=7aO}9_GZl( zOdJJ(or#t83~)G4!J)5%uM8ds0bYY8**1n|7>c}y***N=1N>pK!j(th z3P{`>IDPL2cjJ+?yGzJW7_-nFtjhGZ3t)kcj*YdzfFs?FUXjj~wOzXwUYXC*(@$fm zP%mpl52oPpUKZZv{<}eZc6vZT`0!zv>l`p%#a$=XNhw@2jl1B)q>O)ASzQHdLs{3b z=h#R5r}u4Gq;XRG&j30XT3lMvUX*4wwTm`i{(Xw`wIw`Z_*PY^V-9{#uV2VGG$>6v zq;m4U#a$f&v>+qkz+9VSd6-C&hAPn{Z zgePg9@jQlw3Gaz81ar8)62>!HZ<^uP;rR2*E)qwS3TMQJY4D~tklRZGIqZP)Y~!l_kr67`&C@a;PN<8@ z9jnU<&B+lWaq#fG=$@lDEAK<51_S$xX1f91Ik%9Joa_TSD=Fonv^Cr> zvkm#8kQ$MbwlXk~#hmel18)_OICu`Aq3BrlwYIciAw176i^6W+x@%VeEN2KSD{#5! zVPBNea$}b%Er}q1g)2X6^40F_m9&Pj4WhgPuGZMx+>gM9z!^*SMC_8=?u!Pod^>`C z);n8THjolkv8P|k$ELk}xdoiO+*E*96PKySq~QUnk*j4L!1Qc=K~^!OuTe+gKw;fNUNfCX08U-$kGbrl!Jx=D?5t%D=pp z#$P58)z|sjK{A~)EGc?YCW`GOtaudTrQPqcKSYuef-pw7s9NIbrma>W6O8HpWK6mQ z_5#jic{w>U!eX} z&+Ru|>H3;0vXBb}FMf52%`J-MzO=D|jjKI8vIed@J0HUhzAM%a-)neHBZm~vzS6(~ zgVAlM(kK!x#x6|+c)F*hx@#wgTGjDK*E_&=*KN9jQjj$odz>J5fHOG&3oIhzgp;>d zU{Th=H${=_t!grIMn+}bIuAvC2UDI)Xb+`1+tfB=^*F#E6H!5qI|9E3;K4(|z$k>E3kbA&*m66_*Gs;Hmjrop1QN}?kl8yio;c2H7M@~#Ko6Fwpco8vsv>Z~K=vs-Kf7&qv#=0QBhW+STwEml zsc?3HgF*m@kaAHJ>Tf|{%Dvik{?> z$f3K+R_9~0d+Y0IVq#+agM$^3kK?4)HoKT8j4wx!l2Plc1IQ;>wz3Vjtkbiz1T&C; zSAmTK7S?8+Aif?c1qFoxZQn5>z+x#bz)XzzJII#5f#Tp4sJ1;Xud!|{i)Kp z+$U1~#ug1r>?d7#BqN=2wmN7!5z?GO@dV~;Bi(uFl_h)em`)Pj-~g)8f-!~EpndH= zwWhugiYZRu>NX-vCk)uI52!6+6zm7895^KjMr9tLJZ>UIdGb0sI8?yT_b|LH5y4@d zN#He+w$PCJ5z0sU%4C52Lsfx;?k*1*vP&kMx*(&$#}y5KJ)=m~F->KyXa>YM-Zd zcbl6zY3lV3o39o7qewjS_$b5qR3?;>FzILVupp9j(CH6*tlT2L7fzT;_YB$gn3GWi z$R61g?jTW}!DaF&jxam`O&eM|cUInU8Q^q;;KGkTAYfQrQ1`}KA`}ZH2i|tX^8v^T z;G>;u+-D#ABW3~@no>-k_PC0)UE?`utOVQ~)C zFg%NV4#fO9<(+_F;m#Vv8Zm9hTnm^6bTTq!d>U7FnNFxeM%WH0)X%&Jg>H-2RYzZV4ZZ=AuPhYBaH&WlDdx_J$eb={L{aGTaTQB zkWuk^b+PuykAy;Q-Vf@WS-N!ArD+R7lZy^Isu0=k_ULMI?g%muv>>DW5#A$t%L^vM zT!-WVO5b|#n%ez5!2e0zwC>swU( z$1-KMJd5V1-8xr`t#AyzLvBeTVRd~ja^lCnAQeBD;V%iORaXH0lY(IY^tQ~_SyMbE zix4Z9gHSAVUT{9|6efh6c099x3N^Y1S=?MEQ5UjEY^-5+wRYHD56LFSx1-fd-;dA>uE62kKG@ZrMN7o*b8|{~`(f2w`Ic)WPXvhbiozdMj$a6y-25V9y-{j^p0dj@1?^Y_FK!#At>E+tqLvvm6zZ~%6 z>0bOx@`>@?GUx+kqN1y7G5O8F=x6{q(D;B;5!||OuI>W#HZohW`=7G_S}KCk^?35( z_wUaLb8aBv^vMP=&ZV)6*?NV@!jY7VIWp66A34H^)8<-XafM0B#Bn%G13?c+JuNm7 zq6RI(3=lrn-qp_oi)PKSF7E0I)WG*stNVt*l2*dfU|~W6Dc)m=7q~tGwt%HviF6b; z(PX5R`5rqb50lxT???y5RlUoElOE+i&v+1HS@au;!Z4Lwk0zr-fwH)7DRxyi19#7jHWu@+1UTj^Fu53ZiuO>=v)I)^I-4HC!m+ z{z#NjgiAU&p`>zxH{Xwv!qwFkxzVc*-EZH%5qeRoCfxaGAm= zfMo!2H2|R#ww4=GN}iCB{*xR?%d4H1@trt6an=yG2&xak1L%NRKskV2SjZ4Sb-|4Qc|o&| zMswDnx3`zX*Ifi&r6~*v4~vSPfYQgXeY+2Y83NA?ziws`i>(M!(<&zE0%fnJGM*(S zl7%a8M4B7CTYL*-#O;JB@yhC-J_0y@`!*SoGC$+tBJLTqIF+*N3G?%7C&m(sM)Tn3 ziiGDb6hU~x!+!DNpimA-qXdBy7l%Xfq@!bQ_RmF+xf7wocS_>E43}zPLBokH{G~U?B`cW6__-p@7oqqdZe?m%(#B ze?oN>fRRz0u!@SgAQz8y=kb4qTQp#y7AUqsR5%G^UT&_ZX7vx6;ne9sAlrq4vXAR2JSy*l z(u?b9hN^G?kX-;%z{m-~dL#5M9MTX!wEQdJPYuKdjB3^5BomRmG{Fx0fQ(E$G}{qq zpR>?JE{+ra*0TeC?9}myJ|EzW3ekiYx*7q2n7E0B4Ml`{*>SpGuBE*_8PW(NLo+h3 z50F;~e8x5gLdU_MIggt%Y1Fh%@I7HcEf6_}cQel+KV)E-8*TLyv*~_zZ;dd!hl?iP zp+nDsNn(+55rMd~c|5)Twe44lF|6kO+}!7p-LgsEx`&0$d+?yDB`xR~2BmI=b+7O^ zX6EOg_vG7Y;ByJkE!1iMl=&OJ{>0aZDh|?gkUznRJTcjw$GCP-Nl~#0WJ9JpY``Rl zLg(GwinFgS&J497slaV`ihSc@ks~j`PJ^z_pk=deb-r`{7)l9RTG|mD$BK$j**IqD zjvYI8+1B>#Zn3KgK%o`6%<<*nixNWokNsSAjg35brpD}i%W+VHfD(NQxA<_RwlKO4 zMs7Zef?4EJIcW)LvysFbmB#reeeQqQjvYU)llmH;*V5Vff-t!C_a_hpc-mV#;*UDq z!66GY)YkBsDg6tsMx8FVN@d=n)+3ZgR1(CqMr7eVbO@s2A^iebfSeJtR23DG(sLu( zmjHzXB%yN<&vr30Hz6VLPZ@KVIZb^hhK;vXjcnR1gO^wgtdxc?(_0di-`t_|(HSm>L-)i6B#) zSa5oK9sr?cJRFi2_VXF;DwtnyCK0d#f;Ed$3ov1mrP)y+Aggfz++BfKg_4aRNa8RA zaGnGceq!e%PX`+SQuoEYKfeeQ-{jw zD-GuhtS&skRdOME0NPD}BGGQ?9~45dVDIkw`a-^hn=@<5Z|U}A z_m>mLp?=+kSGEP}TlXsPJ}zClRI}+Tr z+Cm&KHi{-|F&v*4TIHA<>dAYgM z=oFFG*Ux$3wk6;rh|~cZYWR~U2cLDqdY^g3%G#R$9SUG_u5E7?GteZ%GZL|EdG^Uk zofongh`Rt_Fg}Qhjinh++q)xZJB1knK&F_q7Hrx#A(oGHz2-q_5P7z?#Q8Tjb`d#F z4}{7+Nb3l_!Fn{v6x zS0Y8eIoS9nnq-f)VcbJPxd?6Sys4{pY*B6_z-K5q-yxkRXv2i03zoyibIqOT8}VIT z?rO{%+QjstLp#3@v`9c&sq1s|@_dS1V?OiMBiYM1g$VqYL=}dU8~`>3xN3(-NBf}? z0hIT^_teSbI>{wjr==v(<)TB*lIj%Cm;B-dKdX*xHGM-Kn~sxIoT!M%R+MB2heWp# z-H6X1u|u@dH{GN4=}6p7NJ}{XWfRrVZ8J?0g-CH0ztLHitaA`)7na^5_wcCHT;>aLW1w=^- zJVqkW5SzBm(#aWzk`Mr+&>IRq2_3G{+#9YeOF(W>n20Qfl7!e-32qzo&)evYflvbB^u@K0b=}L+`@@y*J${^V{^EZT z3Oi`nb?TO`V(}b3emn_`nFV~9)yJd>d=+dsv! z)O76Ia_oZbGjl(`?j{`uS{7<%SzS~^H%h7s=#(Q=0GvLZ8SK;=7#iAyAM-I*oF3_o z5~L@57}(hfGhzt&O-U!|0mJ2#kzvOTprWBsfNElxa-_Yj?Ji^v+uq_-5u5)ZS8eCZ z5@2Rw(RPl%2(BT7jz?lPfjB5vhGo{(b&U+-&_lZfuzJC*UtDOK5z%U4;T9A)zL48O z&slKz;bPgLPXj|q$w1J&(ND{I_CyE*q?HvPR+N?MFhpNepjnMusSy+7L z$kFP&sm%vQG30-ABM3PhN3RK5D5#Tnv>^5nfei~L{aTd9F0;widKUQ7gWWj&yHO^o zpnw@(?bWFoFVa-UafR4GL`NR|IS}*w>%4!BY2K6+)XgSgODWvAA%;wI>&~5ih?5CO zujS*wyz-&6=RMw-a!73`j2`FbF*I;#xsY1=R<=8#1d9+!lQTz7fGQ}>UX3so|0_&@ zH;>Fx2_Jb`I7VI?x+rKqEQmx-KM&)6hCg~lIFA#;Ccxfl!cxO#1Zp0~H9`3y3Noa4 z99&!*aL_t+e+rXXqe4QDwh6rAH-WA#4Pv0*&QN|yNmj%=KTW<&r;A%j1d18b81yth zK)S&tA_^vq&s1RY;f^L>H5yxFB;-To;(c!3=x0-_y?57ka+Y2i*?T5dj1ILICIL?1 z4^L0#_fbD_w;?uVK7i3k+RL%kPyiqesGJCowlOEpCR`E@&4;nEokx>BkVoLat43Om zHkdt-o5a;X0Ce5Itjk!aAG-ha16h=XI0CUD+% zw`y6}?`CB520uw$_iFpx6A}T7L9?t1ojSlT`~w0iAV>s&!XeN31Z^f{j^S}}p@0;0 z@Y)h<0LfMrB6bck7C@$+0zN?qwA))W4Nu+tPby`lSN6-a<8jp{LKqMs7-JCSIQH$^ z2yzq^9o;6u`6fag0aBnQKN9xeOYggbs~T?UJo6K}GFHjw`4g9xT*RuKC1# z6uBy6mgEJZCx_0%SxX6gu#Y1?bEG|eXH6(ux|RAJBsxUX{;22Lirz1;7-We3Xfy$` zp{n3l$?U2?jPDpptP>28P?_}=MihVPLaNBvK_rHFPJa4yJw?Ez+0rK!6uz4n2HsAU zy85VhWFgp?E=&)+|M<~uphpLyk?QnS&$VB{$1Gl^b|0j5uC~(styNu}JX~ua>R@kQ zj=EnfR8?Td+YLuE1q_m`lG)hU(k1=nwu8Dy2>zI>xtniNegQo)5E)8a_+LUrvbqVi z&A59I`CbmPU)o*5&pIRv3kx4gI$tZHKWZH`d1CpK3NJ730{8=m@d-NHtljr=egFRb z5=wVsI)(lyL_4~s6x%==Xl>WyV9`&oVu%x7dS$xG#Xrphh|;XOplW{fb}BnM=JO`i zY;p)a9RB`U`?p{V0t=-bLQnI1ex6XJ)>P`>qD>F|lM1U2vBm_AbW!Oq8Rvs`90Yf! zO^4;AfvIbF>FX8%MYrzW9RyXk93QOZqnE{JL2qdpQkL8f~j~~%kzenL|rs4$t$-Ve^`jaPXeYf}^yV$Fv ztxe=pDe2ZiQVifIUa>p|4S1YRDK0AM;3X|s@NO`9GqKf_z3$~8sq3tuOkTcgA{icb3q=9LpwQF z|HDiZ5LCpf&wlml4qO?Q<}uZK_pU@O6P_|k_DchmK16c?pMV^HyGKANh{yy!BvmsI zdWme;>ob zFdBmT2DEo^unmA`gzAmxXX9?juc2*1^a7y!;1^cA5Ye5ULr?>)POyJ)kQ^BdQF1|^ zu0mUi7jt~vNtwCI3V?l95>^72of-mCs4D=IUB(# zY{H^JsE5n5F-CDJi=aHez8xst)YG%rAnAz6PJ==12|Oyl?jF@2>lJ0PTi+!Q`-eh zlMtHAxi&pJP=g{BC!mB#Jb}|5PEY4^2gJLa5xG2O#`=AjoV|2ufX zbN?ra3Iy%3-jd^AOI)L|@lYV)5ZW`@TN3NJxy&W*jW3xw(;RYs+@8 z^74}LtfR&-T9S4h3!kqZa~*2Lg517iM+*w651pOS0OO8g(Ljy+KPgHf{{9&1`tM4Y z5-xtno2ef^kpA3o{PpdG3)Im~l$2OzPe2UyCp0nOdywH-pzj4uNLN=Ge=--8M`Ef8 zITwrYWvYgULf-ypxd#%%KR8K!gySTg<)O-apPEv`98u*AN^xqNLk!J`k;+`*=b&b1 z&Vfaxg!>L~7yifzqB<285=sOwQT^IAVJVkce<&Zagxb%*ko^4leVoNjz5wwwVOa$D zAAnK^s+J`dqvpknDo`krkwio!B_*{KD=PjyIdumAC&;8{wxu~yI}YehFwQ~DDz zPlxrI1fr7$V&e9lJNezr|E(T%^sz&|!(;>@ZW1>DDI~NMMNB?o2J|GpBNGFI9Q0=D zS|yxscijR1+XD(!E6(!(W#@G^c6K!=#E!_v`1tvgQ2FSjUaw)+`0@Wqal*t6uuoJ_ zMiY>~WBwGy6ZL5Rf0}a2!5|w+7UK?wq0m7xQP9v}BznszNr*1{@Mlz~3`|V>R@M;? ziP=R`IpTj}W@ZS|dij0ZD$snua3kZlrna_sNMe2gAeV?V9y5oPxh`Y}CE?0B$~ghTD0!&HASN+_8`^^GZ8c>@DB zatd0nprCJs@=im2#mU*Xu zLJ(tVbkZ=|IxsxUqc5d{*xK`kju`7rPv=LgO6b<~C7<+O45+I$kNh0{0yzWZtb>o0 zq0M22LsM69TL2OU4!5&vYA10PZhylWrQ$Oxgltqd`x03wyG$s?IH4MCBx+zW1sHcDT|%n@p|%oCEMH6@B_MtG_xHz?ZWTsk z!XG|NX<{I@--I~Y5*heSxqaK@F!i82?{+)_{R>R6m<-iLRldRxCe#fGQRg%?yfH4Npz4HxKL|$*F#pTP- zrn`E2c0=BjN0LMgcS9CpmArM%vP81%AgV@)d_HE4HCIhc?!14mjEtBb>ECULEmuB0 z-i(U_hBHg$iS%;en_}5H4ZZPgL}bD)Z^jYIVw#@nhT&|?01%=eLZ`gUi;Q)I>~hR7 z-^MizqN~Jw_!6nIs;U_q81QUBKG=GecZ)G6bkwgOtCoe*ayp!hW)Ertvw>{0i zO6f&I@a5o=be>T>Iv*!BoU-DEeMdUi?P(6BH}!g|=0%$oJY6wDNCek2m_<}&;VRmz zXnmLCyq2wwpp7pvuSG#;X=zE_gR=L5{mkqCpg{TTQJThVsHDdVGohW5I7CIa6Z4MB z`-tWvHoUB&yq_ETj=5It)Uwq9m53`s&{r@!xfkUzPK5g zoqy5j`I0y5!Gj&dSR1P1Vtf6(IZ1Y;y&i@JgHHM`NUYV6y!THG|28!9T+hII=ZoiGzG1eSkH)QinPW1t zBu*Jr4;mtAqj@;KFlyxG=jWGw6|`Jp@RUFa<1jHr?~0m-6PguH-Ab$sLX$yL?*Og- z@0poPIGh}1p_Wx3H!wO{gF^s=6a)p<$nDoAu>MFSbS`hreBVr9M)7fjkd}!tth+}E z!SmrmfAqScaU@{4rZOuN{TWV=wMFxZuWxrkFRFCp@Gzq_ozS|kyw4u!NyHcD*K$e! zoCS!Jb`L~afZn(!X9M)aY-C>g#kUxc5~DvvY@PEO8phZod!$@A1O#aDCEwTAE9mMn z6NJu6?@x6Voy5QbMoGQ>u}?Ym6LFjVsh73P6C-_WY#|^GWB9Y*$K*Ws{{5RE33=-u z@_YWA8iJ$$ji zgfijN5dXL*atR+fTWqHUlw0r4_c&0HXm$vcLmaz@201aXQ(ZlPcuR~;c?G72pi@Ro zpX1WL>Yj`#1{#Ff6R7<$_#A|oRR#UhYi6wn;|emXvk`|^S1==v)9dr;TD(1D_ejYp z`3PnbaXe}jL|;ZlL);X!kcg39%x+YC{CMW!k1^!i5Lk(%9`c?aUhY7vb+6+Y#C|Gj zYI#UfzmUy5B^m*a*+qa9Zzo2bPz(@D27t**4NAP96N;F#7k8dt=jFTQsWN(Oi8Gis zkgXPsMbeALI|a^tOb7-|l`d}~5%aP*%gCVwRX{P5Q^flWbY+r{gy!pTWNyLv?~Q?F zWIX`Q2Lk|3Wixh?-F+hjUE)KDeTl9SvPpuYOim)2+vvcae0cUVbY|nPK~2rg707jk z!1Y4|AQ3~mXj)+2i1GPjUrePD9WMcacgVGca2&Gan`77;at>T6E{!xL3bN|hAVYf~ zaN!OH?^4p!X*8}lL8`*Q9`bCWQa*vzi6i*1RoelC)&mXykgCcwuj1Jw$3%~KBL+dj zFf9lwJ=LGU4Jp?b>z4XJeKf(G0r3#<4Vy9IpJ=3U<8eT>iNM8NVy^MPp+mliX~b$| zVWB2fx*kV^@(zUB45PBOsQEvQEO=J|yNO}P4&Oh$uJp(Y2%0+CfvGZ#vic%1F~;ma zhKzisbB$}5mtUxB#BG$VZnYlN`kI1L2Q~c*ktg2X-tt8V@ZfIJAiK#F3d1Ugh&GS$ zTD#WgX^beA)ub0Ug01XggISi(^##|40`0@}RsT5#*1E6n@?UDxX75bjH~*LctMndD z(=asLvU~S#+!dmCkXQW!*l~c&ja#0bqC4+liVmhEw4Z*N^+h#8-CCw}ee!n32A+NN-myf`Z?FY7%ua^5?vtO!NcnldcByW_^*d?1=?GRxo@k$XoKc%;yUWPcM zV`B1jTBMm!0Z{5Q3tv_yKRGvsmI*PxRDr<3BH)XhlBQKc5Yxd(x%o2((K4rIcqz%MiDl%2#^(Nqm%ihdDlvq6?iqHv)sn!E@kcfv!G(a#bPZY&hQ8XeMbxt-j zH#6h?a(YR?&dzRN`yrfu+^*C8WH_kpvCqOFI@45BuU^HWqQsN8yiau za8xQJ8lGH)XtWl?(*BpqloiVNmtG~*QSj^EvQx$mI_Z*mOb*krZ9tBbR}ex-S-J|= z({em&t0uuYOBMf6x%zsh$%X%|bZOh&YWnbhof~T%p?pFpT(M8dLr4OZA3mf)$C}7&x1fB2M(WY)KWHVT zq=c}~qJAUsBThRK4(-2(!niW*kP1WJqi}a$)!B1|n2<{^y0Kyt9TT$|ZiAkUp_u*eIWw!^223*{q*X(8BF4dH(J3oiUwfNP ztRM_OE8sxJwGIppCQaKu!H6>hb^rsgg$Uki@sJj&#qN$hwDImura+j0{;Z(jO(E+a!Y+&ntNHeVP_YY z+S_i(sqf*(j`^^056JA|;dZ0208-dE%Fx-lf7Il#t?;yTq-`;LUWXq0`03SD_DUVP zb*WxhL4*6#0(sIvaeG&amx+)qwGW<42qyMdY2)Y?HRqpuXg1?ORO5C-7R~T=i9T}V z3Qj!!dHCVOvNS`s?OpR3ETZ)zK!6({)u&J+1e7_V4-=xPKXPs4$m-hK9Td{IV__W7 zYc?a-_9~6wTm*fX928rwiGOK!;_Bogk1uw%K;E)|0wQOzoG{fO?m8i#mL#J*_FJ|fbPq@*ztA^>wlfmZJopl_cG z2??9772vH=Wggh(g&f;P`Q`5C*HHElcJD%V&c>8q1MD(d>3>FjCv`%HZCgOVY98rP zUiGcQ{oJ`Bas)L#K1$DlTA`1fWH+YGqMmzJUWs5uXU?1h+gFU8TB>lP9=?{A=6&?= zN$VsfPhI=9i^|H%ybg}(ux)~-&aN>`HI0Y-b?tz(F|BX4b4(X`qGm)IHEws|^V?=G^z&7p9w;sq)`Y2g>RmfSUo-gWJ(a zX{ajS1UB))!2>~L-ziL07a9+Et6tje+kDY7-fqN+6Su8STAtqu@Vt|1Yzl5edR1@v z8Pt0os@bd)Wk{t5B*@D@n2->ns(X_LFztwG?D+^+057jfM1+(SA_wC!q9y@mICIpu^ zPu6hqECV@jOs`CD(B<9=C||VJq3r zsG!pTjA?{I%}Hw?ejM2`#A^??$ zW5ANm6&YPgz3}5!Dpg;%n z$V6qe>N`t;uw}^eN`gOD6t1LQZUXj-QbHa_FzWx(&!6pnJPZuZUA7z9DNA?oM`QmgNU;L>3ypQYPTwX zUEKqAw&j!}eF6{DA96Y4@O8mX3El>FObg##D}$yfJR+i|0>yjXJ?SZoafL!nO>G7y zA;`nzxu=mSDI);IHB>`!W$x+iyLNeiKM3rG;f=Y5wlsy+;xtxFp}FMq&&;of6}1%E zZi^e+bi+*?m}WQVC#e>Uq*+2hMWd)z7VG%1FM5v%9;xX^yAW z6VY4Ux^?a9eBw!h3A+7}c*2*R2ck3!4wAhv8GSn7K~0lbpM0VufLFa5ZeVIa>4%==6IdY`p`I|^E8R}9c1W-a_WB+nE z)$>U!R!Xc-Tkx(UH|`G+qhu3u&q*=3I2|E&-}dJ{RtE1!L}K{w?&uHpxl~85}Kt?;B=rofRX~}18LNGHjq=ilez&m ztWKUWD6qhAR1`Pw+_9SkEns2M28=YL!6R&rr(hU`v_K^t)ZeBi_La{FzFNlSt zcQ@)v20j7JJs`Z zQ#cJasRPqUkMS?+*zMa@af8ICEmOMR@D7yLRvrR&P`_Yuh-0ro7>P!W2{xB>i-nDl zh-VxetN;qs>iURcYCIRjuC3Q-RP32EXpGVi>MY*tm|p|aZvlcwrZh!FEtV|^A=}q} znjhN9Clu+;!-gz*8LL0PZ9VTd_ER5*rroAP@7Fd_xV*f(u}5db)f$uSn@{gJlH3!f z)1tf!Y6`S@ZXZ873zLpFK+VDObrT>IagrnG^ibUu7^q8SaC7qVTor{079C#m@)N8E zjXP?O?WF4EKLPr}y(->%ZBk#)vL%sER7Pa(8~O0~J%`W;r^B6m_-Is_>ZshfwK@uf zd_&e~SyxSMMwUd-Rx6PGB~KGK0w*dCBqX%q3NzA!K#{0D>*^{C`wh@9V@K@cif3dt zs3^rXtM8fJ25f6wC)H>42^r}&2->!HL~IPk+6>Tlk*YQtTn|;a#{T{M;+opUEw);o zm6NlXsn=oD>bpnQK3Qj7aWp?QJuS@!F&=U{<<+A)Fi?{I=%)46RhwUIkYYUk`t6%W zj~?|HdMepxf5sg-)qaG_6|4`4vvOO!>C&f`c^868lTJk!WvIVTVDqY<+hUoZmS4awUlx=QVGi?EOT5Uj+ zb`7*(JKkl1jAk}9D7&Nn{z(d8D>LId)i|5RHu|$aa&wJbBTms5-K_F`{(9az3OX=) zSJA(r&D`YUW8{7|6U!J`0oeDITefUzFmd8MDtn;XAU!R;($c~S5Z2*>D+W_m$@+qZR2RKRqehJcOUC-ZuAthinFsCgxz%@Pj{Is7Yp238I#yZ7+`L7s zZV$tevs*&&?j60h1?^`FjJd_Zox`{)+0Q9|ZlW>HXY?kC*s6nY6-aPEZGA;sOSN@u>5ye@o!;qD4XZ%3Y=H=@&ZdSJ3w=?l<%!!Q+0<5vJXDrP@#bMec!q zOvfK0O{1QS8~Py;N?*8eLDWf#Rs-V@&2~U@I1WSLuy&0QQlG*w%_2}k!OBysg>M}c zW-}};Bk6MgxU_baZv{Kdb;?^tT21~+>L0kDe%6=g|L}6W@n*{Rt6{;xk6t=VbL^z5 zd_JVdW!(Am6HtuQnp%+X>FuMYPoF-OpWAXRnPs?( z&pqVDUUYMX6p<4sxoo%=__-Q*NJaX<9*DCGp=5);dm4c1a=}W-fORul<24{nV8F5> z1KAzp^LH>r5q;GYmXPu@XzIRDcTiI_37grvl7TfqN`|c|(^QmJn2sM`r?j+GyoLZ< zV1rVdqewdSXpv%YiIWt@?HbjUk}f-2f@$>qTGc?bk+FApQ&;VznIndx@=>DYu(7jK z!u>%l*}t2PukRMFR>T3&le~OU@mU|gbikzhV1p4Mr_<8YFLr)4j zkR3D^8jJbpb1>ra2yo|La@X}gzMeDpq$~?5VzkZueAD|mM$(V?B%`!52NBYysvDGS zZYfqfNN|tgMF$5Qi;iZi6{&9{F3#F`D7s&{2+Zz_HNtf5>q$-o7%5oWJ^Ad)p7-Bn zF6d*S)Ma>D#;XRm4xL&)@Amw~RZI7<6ZUqlEVK1qG1c7sTpj1>dy`hiWkZxddZwra z&=`KU1MQw}evd{fDxQ1xOmFM>;CEp;lB%ovLB-}y+QQTw*mWll7^6toAA{~>X5L`u zPx|Wif!|b>YqLaM1vL_NA29=OqtgzXQ2!?FT)ATVT~NAQi#mKwWz?GLpQ9xkh4PXz z|4K?q9SFWfj&T;AINjB|c9nsUQLt$2ZSUi8cB?98VqE1#WgYun=z57j8{26t>J4() z61z6esNwK=)Q}3!k9kfTDF#`$kg4{x6t~*duNYi3wR^Mr#rcL8+qnGf*Xh+|RW87O z8#!zSFD+N)H=!4H{B$`q^zniZyB9UWJvIMx-*ZEOC9-pRnsg8IryC^IEZ0JX%BErN z?lpbn-SLU?+vPsFu7}EbjSh~@eSu$=coMo!^*jLb-MliOIy8Le>a|J7qCKO zjU*Oq6La%a0EWw_%&o)FpRke-d3AWWeZ>;D%#uPlUxntxF+TG}96#<1dO}$~_o_#|CY~&&$(duS{lM=H zi>y1Tj-_)3ThskQ^`}B}$4j4!I`(!>)kM4%UVsk+AL3IJeT2u4LETQ|_KGMwI9j~L zYtzgqx-7}$i}s$}^@mOr(?+*vTh|@ay!q~a8q2A+Kw|XWzt`NTz#1ZwcEPM| zZ9Q3l2Y=kNXHQ+$3n<(0@2od+?`WVr-h(MhLr*o>Cnx^&&)ZPg6rf92x4gY zk=`tG{cJ}FZX)`^x>kK$op|z~@#CqcrW+xiV~mT&Pnf_``7Sywia|5^iQLzXloXKk z=ltm6hz7rqUHT;oiB9Yj$iPU;SOa*JvC zsa@T`lb53T17RqjHN?p6dGn)xMQd;_HWG)NwVU-MR;;${wL&z z2&d};6a%;eOKqVdQ>fhDfsX~{iVx7=Tv}2IN@4$^Xj3SlmlO(6h>xpBEqa>RS|QS5 zD$7%k-rButk1qi05~jaRnI)3O0sPFIZ}Q5T=KzVw?dndR+!)2nFarD(Hsz5->H&(j z6O6cYbr6V_+vXQ>#%Vq2b77=Fyi^t}klYY))`RXeNvYr>omZ@=!xe{zs|#EbkQeyE z8&NNvARu^S_R>OXMuuB0yNsY3428aXe9?YTG*8y3s;4fSqyQ;^#^}eML*@FdomZwf zfU6(5YBCCe8VVLXfO6Y1zswSj4_8%Oe_c{k}(1WGMNknlXnQp9lz9VH${)&;#4 zE8jm zVt++E^)@$dV)qjOk@fi>QUy@vV#@KeoN61Gt^MfYs(u+683$lHxIJv?HB@JP5r+`N zoYLL!xHBPye;HSP=V>Oipy3DII12GVvxes<6>93HeIKL$=YU?Ax8fzUTU4^keIorpSA2ZqUppV+qG<_{E&%>)Usmt zq;x6-UQ#%Wn6LOsFxJPHS)EajR>!W$%*fD#Oj`;QZrWQo$dRm(xCT9SW|W@4BiDn%qdP^1EAuuyN`ePTeT?RrUEm`E70SPHS{ z>gwuTn5rUoM=&P24ueRaYF*9hhim9M|5g=E6faA1HG+mO?@AYTrKDUkR#TH`zJSMl z;bbHUMA7E$jYPckl6;nj(3GlOaV`hXop1`}u9ajM>Z6qan>8jW+Yg;#8Geqdqr@ z)jA9~gifv#B}o#T@%H0US8J+#-z}9k2r1f{83YrsO!*FW%#pOE)sC*M+>Ym$(FoagazFYQMUW*-b-CfJep=-zNRuuB|KB zyCqCe#(IrHb=f4e$I!?0TE{v<8w?THYfs%l8=az}>M?3M7yPs+|a4PNY+ybtS%tm zpxCFmbmqx_$5{_1flx4rWnqAd95;Uap_DE81|jB@jDBfqJT+jI6z#SDgzZ$2+5S{pv`~UGqdUO-TEIkXaw6wFYrL50fOrJid;Yv83hVIZ9tmX*M;$HJ zGI2>K6@*ZPA25&9CUrn^y(>bA2NZ7*>gg+}Z`o!r`FYYgu;ar)s&(v``E?HjHDDBd zoCvjOFHkf!VJ!t9m2^Qed4eBQpluREqohyJ)}JD$EWG(Fg(zyV5!ARJ6u3OzN`}d= zq(@pOpdwucJ@{HPi)8!TS`#bF?*HaBYTY-gAgvk(}hRl3vol(b16+sg8i1MJI)YRwxV*;odXP=othaIW@Mh%7{lx%2GX= zTQnG8!#2;adxMZqU|ACeIcoHxo==FnP*9zSu8x%iXkdc-?&Q>>q~9y*v!G;5zVBg; zoK0jnD7Hax=OUtRHDpn%dr=Mx7tUdO7xa@i-J$4Wu?P~GZL`l=@jj-ZM4nxD{a`t%!kDh zJUxA(?IRE@Hcx?mVADmyKoPAt^6Dg6ZYc*>f#k5Gv^oAlYVKF%I>bfhBVPmrGNHF#}Y?42DA zM^F{2k<$T=@M6#Q?VaZTwAgTE=B!!%lq++9;W7p?@IYGIjIy3m1@IPB4bsFwqiAlC zFn#D^Gc&WGmd`A{B>Yb4w@LM?hv9F(rNVM27nX`pMjCQT5^7GHtM~iV8hcxB?BcJu zYm~aKYS(B>WqyclU|DficJ@_JH)paqL;%6#O=Vt>|CV{@PK#Sh6e=;H5%I+pWL5Bv zucAzvV`GyX^z}tikz2~#dhO3ef-h@MMCwtx{!mPZ{~`)#>6CfLj00Qunm8J)_bCTQc<~x8k-JGn1uIl=y-S8WxsFK1iSU#n@wk+ z@WsE?NLP8_Lc@s@-8XO6_nq&p)%sgI)BzHu=R%B=VmrodsHaUSbG;u3R4i2v9W_Ug zd%;l0bwtYbur26Ccs$c6C3`f1(8-+vp8e)94TU zc-*mmzS#`$<*whG8>;Pg63pJ^=!Pdjt`u?Jx#Q{P*i0HcpC+)!OLbY2`~-d0vu=*nl+KR;CWXC(=DCUy~QCAA;)o#(f1+7(eQr!=YH(2P}e!ah&cyAsdoef0cb%5`Upm5$_*L z>DQFyYEJAUBC=W}&?wc|IMxje7%>7QiE?|BPFq1OL7>IFjL-%oDA1r9jJ1=xdJPs( z6EibCUQXM6hw3<(-wgS-)zb0sv{_M;f;Ulvi1kz8T^2j1{L4>zE*oELxDE}#vuDrT z_*7(Tg1uARwi@PqK+k;ycPSYUsG=S`cp!pQECh_ao?4SA(qeDbyPxPmq=NdeVXfHD z5G3hYS+(==^&MlGlp`Nx)wd<6Jb!*2%p>>sNBZxtBxD6o+YM#*oXrze!L8nh-qBqr zW7pyKKzp|^tR>!-{l!0LG%K*kj+&4&k(As`%fk0RDT1E6SwC?AiKY!C@&F1wNuy}o zcu)7^7uJt&5@IxzPdL9M|2en@u!Anb-0i_7CAT^bb!sR30r(VzczqPGy6%5~E|CZ{ zpw=BWM&%RPq9z$UxH%6sV>E3iM9>^IaUR1sCLE+u%3jsBAkCDwcFl*72E@HyAO{8v zvF*#7CFQ00)jwOJuy+{LNW2jg53Hj~2VOYuPZ*Ii!K!*Co=m>3fEHfD7RoKD41p+f zj{hX+uoXB>hPf{S5xZ>;vm|U6(Kl7)=8zor6{7|V{|oVMOkBFd{aGmQsCK>l{p;*W z2a0P6;^^+?=GG#;VZC~SYlH1d?V>>Us|`MKn#gfX6WfN*G;0FA0}P{#Ek#VMSFdgw zUTm`Wr`YEa2C^eSrUkHDlx;sqe9^xFQI)(TJ&OkjjeNlJCC0MmTZT|a!=uF@T&q>FqbtHS1T1t}X zSdJx!ZuyiCB`+UZ{0FRS80wBGdXu}m2os3+ZYOHwZ~FGX29=s}ZOKCg6al@K00x2i z*(Mcjaz<0Zp$KdTP2@}p1N&A`Etku+{}JOKeE7!tuODk5mB7K)U|#CXi_bNC{%dSe zAK`|2aj!E}z7*d<&66^BFPS&bosMzdqcgV8oQJ_qCBxB4V&MV154OaVNahuqFY<}& z2N!N_Gq`^577f5@@7}vNj+aOTvKza^bGS$m5n!AK9Kd7TP$8rduPUfx=jhW-AjyVS{yWV9~+l~`J9QKCWD z?7jXf8j2k)ieIY%H6<>P{_3mi`dS<4{)8uwkFQ+NewQBbW3{W)h4}y%k#BKi%>2!SNm7`on5 zZ!$XsqsXK8XhB;whQD(te*jSJ5##UYhu)NfJnj$4HV8tQ7Vv!;aeFy07tH?IQmths z4WFy6e{Kh+8Okf}x0%t!0>|@BiQl<_@6*)8M1g!6oZjHmtb%Vf)V`e32qBtlDJI>YNFAHd@x9fUe$y_pMmEw9+Wob-1QCSa9X4 z^0>#|I_^sK*2SJ1Eh&|lDo>qwaKKd^Dc&OiuAAMe9`){4V&K2Q>hAe17GKV;#P%8& zSD!B_yRG|p#xEGV`(oqJ#v_s*>}(D~dgw%D;N+8s1mZ5vzk0s^#!0vT!mfXz-eoBV z+<*J?r{qGzT?f28u=8(UV%>1WOPao4e`Q#Wz)2D5&^!n+5~ zO(_kHIk{`Imt)w%H4rens@LVdJ8%zoFS?^GsE29qI+=2aN^6NsmQw`ue%7g3<4>)e zhRX)N+S%Dzc3|`%PZvE&s?A)Tf$4quySH!s2&OPbP?3G?l19(Txq>$kTCR67E6(Y% zZ#Hi9Uzl=(ipxFyA2je;`1*V=+G~L1>lA;^fCfYEzkO`W>ioxrrSn2>A@AM7u6HvZ z?EJ^H6~`WH6S{IJ**m=={Z&bmjvezCCPEom8tYFT)M5e;vogoNd~(zveVQ>``!@FW z_3Z7_Zlr*3fZKdqkY3_E?CYz;Va_z5Q0?Dh!ydK~>)4GOhYiP!>hPhL{k_jr^dfz7 zY`O;12@)qq(?9xc)U13uyX)lc?|i?#yM=&3_J-E2gNNLI{n%4=6RpBCn)roNE4f(_ zMJuFDM{Xn764F$Ka&h&;g^nq4lXraD(5HZne-p^<@;+Ux^98ICX&ZJP# z3(|Oy#Y;#why`WX6}#BbL#tSGpjA~-Bx{E?2A``<4s0h?gM%Aj`Xp5c2pHo5scC}8 zDLiibvVkD_TP`s5jY8>76>UOh4(SrjF3jMAg&oQgEKNJO3hldLvtKAG)f-pLU!}T3SPbxm5A1R|Fl|e z5a(9$%jy8!EDnsJYS|ncD=nGG$iOnG`1+S|v2wx%zBZ7`D?Agz(&y%}sK_2jWh*-> zNISkFMW?+VB3zCwxxDgELAwsMJl0SNn=b6ycbi2>45*PVa`f$?p}m@=f*&B;{1rMP zG=|trMDRobt1)`?tnSw4F;?{iIv|3H&qqmTlYQ#+?>cJ6PgdIE*c9?cl=H#^K+ycN zH=x`PfDIjv*1HyAnPjc2Q*|TM?5^2QOREWMY#sI5WAD8)n05WZbkqCimWwh9BP&*U zG?Ra|HgaqfbtS~Q-POE=6%CNPu*=F;$y|o{ta1N-H4f>kphWE1S6G4Pupd|d{F0;y zi8-tg3$HX#VDghjKaO*3NpTY%8R<@J#WQdq0WvWNW}ym1nrxu)1p8iHY*Y~4V%<%*DoTq__o$3`Zosy^tIhveOTQy5Y%*i)CODk| zyJ98if+63P2Er+l=f4Z*LG=Ovzs>-TBbKJyzn+s5NZ_QXxcO0=*hixK_J4gEEu9v! zPw(ebrauM9K=f=`&f(zoWcJ* z2@tZkW)jTg|EBf#^)I2x^G1N~?dPXSNdx)p!Kj$15#Q%_)4yc!qB&iQGiN@)i3s2c zx(fha+KI|T>pdlpqy_m$<@2WHrVTk@LJEJ%1WjI=CS(8LC|%`vQ01k|mN}e@p@i*B z3wJOvaWB^Hosic}7$B*m2^7IG6~G))(^aOUQKxC0G;=@o6u@mGs!?$TB>rCEleqTF zR#lB(b2GHX|E@*%E<4iW`k^=I7j8lrw5pbW32#)y4fDk42qu9yjpwQ-P#}QPsmSA` z*qfA#U~mWZ2alXgiB70eHR#?vwx_;HNeX7I9eUxR*(HIY(Ob`nnP_C>#Z;e3E)x{3 zI^EOt^mJd0pkAs|?rjYU3fhi%dpmXB6jM_jxQ5AWEqX{I$6?1YppPt1gihVTJ8!BR z;xr+|(t5n<<2!sx09D|Q(9nsTO5=s8^AW3Pk3N06$YTZXE}}r@E^vq#umApTsIGx= zSQ#T+tGE~OB6J};@m6BYFaVckn^EWgJ+?=^>7nk?+xqfe`G3_ZQ!^Qu@((IMy=rP` zV9<%@eI5RZ*Y7L4w*=9E!*+F@nm{WPz!MVjdl?Lz_$K~Xbk3kM4(wk1Ax{(6Tzi@F zr?TGj$G^1i-h1S_FRvR}_|)tP5s`w^PugH^WtDMug@^KW?bYuQ7AH2E))1h)6o&;#SyN|1N9y6~T zO~Y?WzA2kv(_k;DBl30g{N-2!3Lm4x~&45 z4PXKCt&MyePu@Q01Swgq?)9K^#+c)~?lWeZf)_6~vlW0h=>S%OKQ~EVY`(zfD*JF(ziJsZKRHb1<&8HWw!v0BQe#$(p^U_zZ3k$Cu zcgT6bS!8Ow`C%NEB_#xPu?|u168cBfBX+7g9>D8TmVm7?$bceT0;%jCG5+m0mk=w%tZvjmR>1*-?p$i19651zVQ z5mgVcFz;176;o$#jCy>}Lc07pbFTcLK&hc%E4_iHtMvVok&3~A>SPw$+&ZjTY}%w! zI*BC_Xp7MuP@i{_i*N$f!}8WVcNNB@6VZ*&PBq>!j1yuwYQU$G?0eD&vJvi%B z>NzO3p7Wz-4DII@l018Hf}9yiMIz=4rXSWwFXsJeXhVkCPV+cQhj151`wrd{AF}&( z0-~3s7&?84HL+7ILm;oXf=w*w6lfkrL=!Ew;}`2jQv)hKj(_thDHzeLXrpy2Irhy3 zcB=qWm89DbYq$00=mYe}c3lU`A}UDq(YD5Moht$kULNAfrdSSqcv`25tn)dy?y}us z$MCFCOX&&_&j8c94qeAPei>bJu=_wNh!+V*fB%N=E|N3T7)yQ|$n>%sYaTse))N*8 z9c8s>O9m}tYv8k5oem!EUKw%ZWJ?94vnbdRaP%KAAQ^sKB*f}tB3?%!1Lov6H;^F- z*lxwSHiWEoH*ah@f5CzVaW(+=hym0bu7x;Eb{tMcN?vT*4-{U&9B`B&t;rT8*B@Wim=tn~ z!mo@L5v%i5qmw8-N$?Yq_rSGV5mvMvJ$_1Fjfp4rnXjPvQCo8*yX4m5o|9iE*gH6E zQr!gXh;l;lwc5P}Cp(>9_D=vgi~Qh;(-lNIT%)3w!!aOQ#ms`wFXQQurT1fsIDM{w zB_6+gPkgE#(EUStoF4$@>hamI=HNA&h6&!|tP;q|P@`Fx0L8_;2iojj zpEUB@g)INrYWyh55ecJ$GHJ8oVOEyV))c&Ljn`6t(7cGao%T|<)`h6tfYeW_)2%HV zAWkK=vayG%u;XyS`joBDNCJdo5Jml#RrPAuv>V)TVZ#3XBUf!59(^EgMd9CY_>7x3 zRqH=)S6T5m03;HZ(K8%kKxP|xmh2(!yk5iOBf~Q5Qq5z+MDW-M(KNeiIAF8xPtB~! z|8@nqh15%?X0SVN!z@-&+7idd%|T5k2mUazPEk>&zFVH&dGTQp00yjlP(}cpM&G`_ z6`d}oO8d$#Pa?SwEs}@{psxG;oa9B3@u&FQ^F97f$TAUFQ|-Vc=+^D()wz3jWn^LO zax;?FkEV%0HUStXXI#OrF|Y}xFHwrU9Y^IhxN>xM&Tr8P!axF`%ds2+%i}@J~{IG}s$%+So7cx;aw*iQg891)Kss{ z`kK+RISn_sA?vf4R>08_>`0;+I^RXCstjTrzJ4Z;pPG%F5*B#>VW0_I3tNz!-)dy! zGqW`Mgd;CpWC>y&flC*Uimq+!(cgdn`D2auaZQVeP#7gSmysGD1-P74R8UZ$TQFwA zdgLIq^{tm@Gmyfs?YT}dwg~|}3h%KjEKE|*UAxR87Y6~ffTM?4rE~zHN2}n6BqS0s zmIThzz>|^~+WaJg00t!7x({VN8WBBIJfQC3hYqD&Sm(56m*!U4Wlm(pDD6Y)DoQKT zD()Y-Nd5Ou3gSM2t^Y0SL01g4aEjLr+h*a4T1e?R!xw*MjYJ^ac0-WZJC2uu|S z&_Lzj22WwQ(JuzuentomttooCCC`3#$v)OXeCQ)rHl$(SgjNlVf{cVT^PP`p>>reh z*^XWkm1P|WbyD)`frSPdq>7zRtPcb&05+gn2K4L2{L$NNzi7;^g9%Q5Q#tRn4IM`U z5d@rM+Jgj>oGUn=Y0`6-GyjWb+bQrje|5uz+{ce4+)Yy9aou%m_7l`kNIF6$NW>G# zCY-p=-00d%D>h}15_}#tIK9>tU^F^dQYo&|zP0{BQPY_!526%g=n8_jpnJzQwrTnp zMLDxwIk-RyqQhM(;tp~8UNS-k`C*jT6s7Ijx36)3??*>)a=uQ^Lgs=f3T)4rc^x|p zS1$emUUE{9)BhCKU#ZSt@NIY*ssF$}K5VlH-kJlz)DFwsGc0jzrz>zx$%Fx%Jh=^? zNw^?rvPI9%BOrr6+f1khC=16<=U&PDCkueXDTkh00jYIn&DvM_;K_n-VbwoG5-wA- zzxtQ>V$&VNU}bKd-+b`%p&^u6tFEt&mXr`G{$_77|Nn#JI!VR)m0<#+Ih1d^ORP&W z*G$6KDH7M`0f*icO|{V*)AM7(;uf~v zRiycN|1^`np8MK5w&?VF+eJA5c_XiH;_*<>$3AWspZ|!9-u)Zgs(N|Y>(>ro^%2S8 z-J0Ech##jRbM{cJ-|8P~%_b#>G-AofzwTDf<|QQ7yeX~Qwaailf2Ie2O{V_ae#b0n zsOMSyq!MJ0y2^p$e`>tzAL^0&Ku1>&9ZDFYrBxFXFE*&h2AypH1IE7}+MePoGHgwy zwVu@|@Zj>@gB{kQaGb-D895GThs&bcamC4W$swD2-RtCWwL_Q6Q23xhMt`}da?$-g zA_`Gylv>k4$pT-g!?c++$AX7SJ{}7qAiM-oXiWZaqS!I$_oNNg9cZGk*4ALbqb$GL zZjiq5ZINMT=bVk!S+GuX_<>@_Y#gVjqhkB^?Q3lq+HZ?y>A@c(mo8tv^X145&5USr zG{3oKm1w*=Kf-S66d|MNB@z}S$xxYAEK|S1C`CKHR=z?w&lSf2)S^E`;X%eP4-q^o8<>d9ZH_G%D&y5Xu>)2=Jxt~I=VQK zY_a5WWt7pyB>e}Q&iw$OMT-m%MspKj6Qyp+G zS%&SG?koBzK=rE}*M$_qyoWKk=Evl^ z9S@+1?3uF1KofdRl1Snm(WH^9(~70UX8!!z@Vag?cNPGGS%bx%0OxNdeR?Y`zyr(R>p+CT9#x6QR| zL56SzT#=BrUb?!vchQOyBR}ThrLelxf*B!$C)%_NF!;3N>?>D}KPk<1Jh{Rr5$OS- z?Bzj^8Y&f5+JCcpwWyLT6O0cqgjR=N)>QD~x*`P8LIGVdIXg8Mz6x|9TnNpe4OO7%5ZOBnKaJXx*C{(Yg9j!; zjvhvpwfl8<0{qa4P>+ISr&1A2+wpk+h#GDHkTTdle)%G}H9)7F*eaukr_Qe#93~FS zXqFx3b&7RePT-VK6~-DmxhtOOJL@Va;U$=gfVaj9(Mr)3#gAy}oAN6;{LnZ54x`(^ zD{SU@P}TK!{p!p=s0&}!hmkM%HeGMz<;%09-V!Qa51@=_lg_ACX*sSTB$5zAfIV>| z?Db<^WZ`Z=B@Ggduviw!mK}H&RL^n@5=lL7oHj4%UTbV7NBtDAgEQd94+S64! zkC&6x*2i3m2SM#`QQcI=?9XVJZdshU%X{bz>>) zNb$IED)sYuq{2eh(+rgCU(0BeFnB!;HOvGaB9cZ6%dth*2(LoWoc5#_a}vv))-u$D z$|RJv)IMb=OZPLRPI|{WXasnfg~zR?HH^Y>2+__9f8{^)X(x>csB2 z&d9NclP4+L(sH7!b{K0BS>fo=ua}hDvzGA})25B5Fd_+0TSJ4hy}N3MP3EPZcn$Mz zOym0EeYltYnvUx}LG2i7HsQRfCOBcD4^~rf8uNo@R#ubr^x*G5@dsQD1MFsM>gJt; zvC1MW+8K}^c&2B+e%<(3Bo~LlI5d78_10&`sj>Fj#HNo2n%YHJ4n3gR%$bHj+C9@2 zFWE;P#SXBs;*yf(4*@sj#54ISaDqWAUYmuW|7!WZuy7nl6z_M zK`~ojMdc6=GXb$ai{#ycYg^*a+~aIGdMobbFugR2R}DNgXsN;}xO}|5)!~AFO9d?G z&Y^X@_#bh z2RgpXPYUyD^R`k*oQjGHJ-wngZzi%LMA1QVT6^m{wQH+}WgcdJ_A;KR`Q6HX(HC&d z2)Pem-_GRB^n@Gz%x5{d^l69XS=!@X(ZR_-6UQrXY7qJUA(x@zENv-z*W6`{UDmd6=|hm0;7C<>J!*{7AGx@ zPB<5)p}|88XZ>m2nnf@Q%r%Qj(V&wmU*W!xw$-YQMg-M=7VCfa&Yg+=*m09h{zV5m zn8U;bTL2fFu!`T|<%K9%Z|>=!zjE}g^4OjE=m5hHZ{JR09nd?NTYlo`=q0_og_{_J zxt7&q|MipW!>(erx-iy`Eh;ZAwd5%xqazSN7x!}zBs0Ry+Iq4uN%(Ve@g(d?WrPVL z(04s&_{bxbVy$^b?1wZz-pneb%RC{6>pfsWGF&UyCyP+ON#ZQ7{x>M45-P!Zvp z%UAT<228Rsvt%BIdjutIp)z|H8XfgXJa=|FA!(mJxj;ecaDBj9BzKPk{}8Dt<)dU2 z(6PZ0?e;sKlU=hctd|@}f!7XHP{R3`RgyHvVdY|;XJblzG;VzHN>U}D{>9t<>-!qE zx;xj-Wd9EuWn%1oMuue89)f;k8}dClCY}SYI3~HB_!=IWQ58zS=U><&kyu0=+5 zh`@0o#~5)OL9eD;ZWN}iE*NwMeQ|KGEuvDmbUAs8YC^VcaT**bSTh(aQcU8TH*fGg zOL+o*B74HUOBe&1_ODnQn6hTlz)Lm2p+b-H6O!qvxV+$3`)sz&^kwDt> z^Q=P~591CbZUk;@YmdMRIZ0i>LXe*1+ zzs8zz1!J38EZ6p-N6+(2t`-S{#_Z{ahxZwTNM0$x#{{R=;5*CCMcU`;kAxK7DB22~ zgc6rIhonfe<3M(n^*=1_fSf8Q3hhBV#l zoGL5Q5Ky!3#^oAPTv4W{FK#z%!JT&COgArV7`kMG|Df~lsFJ0mg;nm4Wl$Wa+aH^Yg3ALix9ofXk>g65if)4`)$h#d6T%O%) z#!1o$PX%NYnod@j%O!ME$Oku5RAF)DVqv{WuI%x^nvO+^HFArffqY2G2i17aoa|H7 z{qfglIY#6wfKK{NK9BnLmwxb*vAIQ-*h`qF91 zDN_VFD+cWvhtqxoU3+p*VF6QJuC-4G@!`7D77^K z|Af)TSFEDN8V@M~y|4kBG$q_>=tprt z7}-OoHPfDMb|`Kcwql3yiRH`Jlp)tQJ3}T-6s%J~d>~TOM*$3X^g!)#vWefxZS#{m zZNFbgTp;JI72k63`_4XI2==u1p-gZ_t{Abazf}M1$P4YY(+TB(8189Ji!L8{0A2s+ zu|h$iV0k5ZTg{mewMp zvf8UYZnG$oC_1i6*g1q@dZLxoxSN+H+@G|7@{InJ!wkC&&7;MD7W_&rVakaKFg$XO z)w`bqISsJhpGx!h7C`gj>G=~MmsPrnx5wj``pwBdQx8CIVB!XyLn~s?rK%qXvNCG9 z8qrqK67TpP*kWOj`qWSD&$paqZXAr(TEg`u^MhqWvJUXNSbJHmS)tLG%1Fw15d?BH z6=j$NtVzVM(h6+sK#M7SkEylwHr9L*U8ApCIM|qAmZ9nO2K}fvjg12?0G^byisTqS z{;wqG!+1IEFx*6$1&q^7U2*6wHtL9d0oVD~&}s2NbmG4CJb&o6)`&2SoP})Cj0AWk zq391pMM0#g#IKvo_D-FeH_-ztNQ1APDzAD|AA&{NML zV~jMi-#vP|nT}~ZapFj*l)(UjP22O{I~TsFOe|ZF5www+T0l2SkAID~Wvg@=JvL66 zVx_&Pf#WiI@55ImlMdn6`w$vxiTxtD3}U4-6Bm(p(Mm7>ty}dGQx9!$k@j6?2kR4H z(ZcXZa?Bc!`Qe8C9}?ZJ&w@wChz z(rk)8Wiflm`TG$NBmA>I&v^-rX|irW2L(F{2zJ)J@8Fl1=`_h!^#QiOrSkBB$Kysz z{-p(YFkYJILkgR2oba~TX|G=6*nqE zae4+6jzsEtKQ1;2{z*GDgYYxDVbBbTC!s!`6tkB)Y%k|5Q}d7*+vn=Yh~sTe6H3ON zoPvlHGz*KIXzi_o@?NaSZX@R-P(}zkf&G;$pNlr5XWFmR4yhE?(QNQpbT!Gy|9Y0+ zI6fSI-p-{*v!NRQ^!q(~`BEA07=fA2BP+DGt?%bU5B+@SWNiu6yD-b}v2@Q8+aRk9 zyAX!vEg3_N9%tLN-nUIpBbh3qF=G>CIkEcZcX0=l+|Ek;z&Yd3Sw0x@GPi|52l;Xd zT8~&9qYMOU9a=WgbJ8LyR4(3NEp8?!%J7d%QXdT~yl-J)o7o)ai<7H%NAgJW4o~=5 z9#%aEBr(q~zx>uJqWeJVKHeGmfr_pZZah*z-GE)(HplH@T3x|yhNjXNoWAucLETvC zlSzq$2NzEZWqK*D6-lMpLg)j2CKeMVB=djw+GAl5$6*}B1%FzzEMuTBmp6rQ)19P7H^dUeG(GdpdOnR?<#yV zqZ-Ju9@vp&HeH{))OR%=Q|M)PD$|m8R|VaDVE<%~X^Zo4S`&{wy$?de3!T~~GcC=q z>r>{JtR{HK!!CY)y7mJGS_QXlGR^hyQqZ%+s?T!PiTQ%)tE-a*83G+iMObk3Zk?dy zmqtHGF2w^hXF+t9I*#7f^qqaICWm(Z5TBhT7L25-&uxj99XVb*a-Q?DWmoArhJWb7 zhP!&^pmqEE%`R=^GI*M0*J)ECH@CNJ)73d-+eHf!e(TBc5VsPj+2U(mINp2qo{(2A zD^~_CwLX6GB0SNHsxg|{%CI+m`NU0;(Y%R9hr9^R4(V*G}PZyVEfn`fN%~fZP7HLY=%Cz ztjaK$`s>@Ve99?)ES<6qlFyd9c*?I!XaSU_s-|7_Y3lA(XBNmV)O(i0-ACu$ z(UC{rUy;MXbY1N4Ej_YhGWdGt3%&{0_f6N>bG>k9Zv6}L*7-rrw(mqumYg5&UQKx) z_cw%nb==EO!FMG1Id+;r;L}^!&1?PZ?_GxM(|+kXZIwCryx*M{)1F=m6eQknL;aIi z8_a((J6*=jpRl}NBX^Y%fBw|3Kg+T?rPJ*f4*Tan_#Y^LR&m{Za(-~=lFLV@SRFO1 z4{D8v=%jnx@0F4+zyr3~dv4c*F*V4urw>+`ocQrG=E#%}#_5|%GxbfA#CnE`>CfQk zpgU7acfUXB7uY>^^6}AJL27=^ZMA$=$$e8EX|0c z?%TR7w)k-3RWry!pn(;efA80PP1UBX5x3tN!B!bfoG3@p;OdBKI(Y4hnU`IMV~)>0 zT2}Sr2N3(i*QF2(iDvskau35Xp8aEK{F;&LW}{%~F*Kj*yx*kF8b!qcJoecuMpW(W zQO0p5;$2l@VzWyhc5_xWMxZ zbE%$2*2L_n@}nnCq&S|ul+&Y(yginz$1!KyZ|qs2z4ZC@MmsaVe$UQ}L0@x?wF`v$ zjoyjbv%Hi6W^N$Z|Kn&GQ7ocjSBUd-%a*zVH$Z~baGO+>)X*|IL;Gmi568wEew5aQ zp1H6b`l@B$U&BGgB`x^Q-(dOnDCPbMmY==${|+oa`=4NWr@;T)uzY^kS*Y-p(agh{ zNVq(x1qzV8iEJG>$y?$y!Yoo7tXzaceMccA0D|@8EID?1Sp1I&VryK_;r-=6 z@{1|Rt|9oxRxBx(Eu)Ta&9xLc@;GG6sN=iuOl5@?_+4=T-wYLBU)rR*I3p*8X}3oM zqg8PRDg-;kRYKapgfF0Jp1!&4Tb;-iA-TJ$mn7#F41AM;=JQdbXq7nirXf`fk}*P3 zYC@mpjRq0!4=HrViSkYq9-5l9fdjP45I&G{(paPBfj_nm8b5QxVt@USEjxB>OjH`g zmO45dwBp2u>+==r&FYIh@(}RZf1v#C-@g5>P^l8j4e{{F*xEjlQYIHGeVHPqs+mGs z7nsRx={k-6BTMa>*r63JE%Re$l#~bw0V9Bc)lvddK{@ydE(a!(n{q5LcD-u9A&F9ZDF6Mpgyml z$vFsB!(S}cBT_XyLcoOMJV5d9BprXFBg&sWv#Njv#L zVt|{fnPTAJTu^cu$jBWI@>($8zx~KSI)?d0=MNnxSA>tfN1XOi&KB|Vf}Js9-7^Wv zWJwP|0fXMs1ZH8Hx%m|IMMldWTXqwf{(=P)a0TSWfmVfJp5d#A%~CVoH)1ypbB5>l zuV3#@w_exf{14)wj9L8|hWZ@;;qv^t#CJ#T-MiPkSWOLAtPhUJCw8+q7+IGl+l+>Z z6TSw4C_rUCzluXL?e5*}f1XT=7pxn95Ywk0!uO}Yzv%;<{1-$U$pYFmV9}-XQB&`o zxxhiag1ysd>cz#y2@fgfsnS6lGn?RJVjcr18Y%F#?*?M?d#56F$6;ntgo!xNjoh6 z*bjZ7m>8P?1BY8Ok~xIv=5;I!5gZxT*BZkWC-M&IYh{}6O8S56R;`>fW8nhs2cYV&m?4(ir&NSF{%^J}>jFB|d(=v6PBG0V# zq?Pf(cc|gj$r^_gU8uH_K?x=-*+;;BvZ|f2O>Y)cKu?v-0VN6rxZ@2Vp7~GP^@_NB zxdUv0J2T_y>Oz&>*}#^ttGm8m!U+KU9DOi}#fpaiBYhOn<4S~(yn8xI=fN3x&_b)j zXeXTVE`)!2DwGOc$^hiTxUuMsZBWAWOos-`*gv{0;RK2{Pg{ghu;F?~VO0n5CZq$n zKy>z^ci=B9=o{gQ#?iLp*avdjv*zLxF!^H%IYTBBH22>i^9OUI?22v%$Z0PMb~@I> z9}Hzhn_PWPB^c_vgmZ+;a*JOGfDSJYH0}v@z#G_7uW8rB?IWg`$8hZAbGyNzuZewf zXD*;06=whCt)9}cZWt%VC?St5|DnO?lLDLe=&wAR9)c%nrJ zL7D(PCP)AEwd%QhE~L4DYj~wm^wfk0f#sJR{=Iv~qRs{v8a~u;{K|vFkA0dxURt95 zSlAiKK;sIUu--FH$qOQTb|?vd*KY4BT|G*|&;e4x(7`;5^ZGVz(nS1T3~YH_oU#zw zqxP;Z_qffpKN^FjfR2m<91@O$*+mUF04ko>f-0ksXTA6QB*%o}qM~OY?_yU6xf2x! zj89zmEicL}-ES1e1+DmuHj~y9sRRl^Poiy~v8rkxHW^dL7IShsSWckt)1Q_{{+Y;Ecc@d|SW)eA z#-EcaT(XKnl9TtWgy`cjYxUh^{BX_+yon04Z2zp4EYqb$X-$K_S;21zfkGl`V@fb| zASYsK>|;ClqBW0Fs1;72heMk^3V3lO+q${U!i6`ha9lDAN)GYY$zjLHDJmUHo7Z?r59>+RJ0y# zxii1b?TVUiEQ@kpBNiUcrBfD#EtON+b^8-baF_i9lVDV_&>zii>$Xvx%s}=a|8aBw zkY#8Z(1dOrDaI0ocv+DkoKNgRR0us$(V~dI52VGKE=0GPubMM>zyR^SczF%{i8ctl z#A(m*oFOW7(Gp8R!63)kkHxoFyjFYd=Z1JSgyvFEkkpknd-bUOQ>vikPqQGBFXdsm zoDQz%s+NYfZF^sOdB(v93l=57NWGW{|8^mpgM)(Hyu|Q{x}?_EBpqJ>r76Sz7w|pz zU@wJa858{mY*m+eD7oPmE?!*j_;^>=u$>4%e8nVGn%Y)0xFiQeo5YL~F;|XZO_db~ zjpBQZn;HN4WmYXYJ^;A}&qLnPtX^%aHOWlVd$G;ca$$PvyoSXzUCC%tkZ48c;kjNu z-_|x9C63c0RAF+mlk|(ax|=c-zXh}pIK1V|&u`?ROadctwAzX z){w{jYt?dZ;eJhDm`PO6#IALe%uH75_){f|w`Ke`0N_Dm)~zxQDv>=Me}7o!F)T8ZxrGd6R-}w2Ljxfcnj}+{M23iDSR_R#DybwC zr9zgFMUqOX2uYElghHLyowfI~pZ%=;f6lqib*{56>)Lyf`u)DY&v4)G>3%X@H@Mx9 zrO$*sB^@1QhM1(?)SR=os1}S|{YsCZGIOMmhw+K7%O#l_ELYsXh+u1}AACYlwq$6( z8Qacpyl&OObL%!qPKT4%*@n1m`JpL%UVsUxpX3NIRMiC#mrz#qCW$hR9QgxrANonr zzn$-X&)Q&_z6|Orbg$z}p*=4fHEqL5(F5`6=Q1K z&v7L)yhaZO9}1n|-F^+T=Uc)b=z@|IY=2W+tOEHgq~P>E;sO9h-+u1gxwUr*7)TN_ zyF~*6!#xO#UU7El|Bki?8vOr*w(r7@W}J3=Zu7u1XK9XZvM07M7vHP*~3u5OtJ+qN^D`0Si$o9s7Gsdzh@x0I zRn_!OFeMzqDs+ewcN9g_XhR$S1J?)eSA2guGOcjGJ^4bYJ7je0hmRknXol=Gnx?jY z(g(Km_&%)@Velc?H0k}jXL`Km$`p(dp9r7*2iV9RG@TD+YLR%;c>5?bk)rb5QqdPA?}I?x<}At4PQSV5J0gsT{8_>=Q86uE(d0x%PLC zK6(5Y1Wy-eEHeUjU@kufOBI@yRp-1rJr6 zcAmvDBk|&tcbL-2&{EnR5rV2k*HtO+ru+!~R1r|9n{Mxr&;T9B+zksZg$|@LM(KA! zRN=xl449w%6KwwppDRbS@zYGJK-sV+x{)lT&{(_(Vj)ZpR|swcv7s}DRG`J$qQ$4w#S6w+O= zQ|8SEKmb0IDWcTsYYy$||H(WqTixzJ>B5rD;M-MIYqG`#i@x0~z7f%$w3l-O)u~`^ z)bFyvl_=~ptrw{57iBc~%BIfDxS(Wt3?R89c#-;tfV%@YyHVz@_qTiQWR?A{py*LX zbk(};$AY( zztH?z3KBHZ%x@LED*5CT<5U)uv%%TPDSlwPUHiNz3PY7%^vNLTc6US!l>9<4#>N)E zFsB-!-8)f7!#V2oUnqN)&6@W5WsEIrLS^mskiv7EzJ9pA-Gy+VJ-7U@@F8ZupdyiK zYTYq90&#A!+gnAgcj%_lk$f=-8jIj$1CB*bPK6901G|-RDUx8V7+hXG_*g5dMMLGh zIKPBG;s*wwTv-T}s5Y;LqiO&8_aS~rE%;zi=Gf;ibtG7qLkid2HGGIihT3g0RIU5q zVZjGZ8&b$+P>?Lk;lw>cjnG6W1aDM~ML|YAD!bZkeIULqhLOPaav^f2j&pGt1BEDq zWWpGF4q=HYr4hFZG|r+@w2q8lQ`;)s6^^RDWh3tJ=6 zw={>azbXJjjXNNdWw==#UIDh8=WxR!z=Gdx00|7Pj1~gBvHR4MeVQvI0D3o)b*?#i zNlTXo?bf8Nbo`RLZV|XC^a!1MKBC~d3hFl{){#i+&!5*Opqwrzdww2xP0d#$K?16h z;p&6mC6$&o{}-XW+9iGU*a5WvoxmBnO#u-0&-`&RAV45(bUYY|l(^?)rc%rYna2%( zi$;x~B-7vECmW8!0*3{re1XG7@#Na>6o8*u)MBrADaV(c^L)&&;tA| zI4^-QC=l6T63~kP5}#$mXVp20>q@fg!WPJ|7%FM{?Ro8zLv52h{6n5RN4ZCzBx*t-n|+F0U?D&~Eq3znSx{|3i9+tJGlmP@Rqc8``kw{AUq2D&+ib6;>iDL~0- z^NC8myWz$(pAx%MgHrVG2GHa}4jha;t`IvfOSI1Pyw1PgvF|U%z;&x@;jCE0F>Iy~ zZQG9k%=*F8{6I)~gJ~V?O(ks|cOAj76aB})3aMo+kLAlHvGFg`~NimE|+FOUI6STQ!?J4OUk_MZgA6khOY;;g7b*3E2#Q=J%j;7kGmw@yb81rVlbUM4@N@V0u*%4Vj@7< z)LL1267vN2^?gD=Ig6f4NvZ$**n@;kU&}Qxn?JH{)~+O#jW z0C%>oN&wo|2h4|eKkaXT;BXe8sh796SRP2i+t0q_#|b%e^N&CF!S{HZ?O#q%?nUUS zGhtz;K#XQ^rF^XTZd@?z_hZMVv0j0^M#Qta?Xu46_BwXH(1&j_V$`TvyiO%07b;L%5&DlIEpg>a$41(E1*_T&#$2c*a z!%eC0rFaTu$N>ZFTs@uQ_=wcOx!=W|KmR-S(AV5WI;Y~ss2*S@9vjx*Jt(D2H$T)m z{fv=nCyzvv)kWEZHEr)+Zti+Sb?co0!_q29$HzdikVB?_B3q>v;zOwyIgFS)MJw); zSZ+pqvS6Ev6VxHf8a4<2Jn|wMU`^(q(}+u`9s@S~N9{r7L+$QQcZ*C)&|{)nO!`=` z7{Fn#0b?NmXa?#6taQooO?G?xt3Lqw%2Uzh%j9nnvw%0pe2|lq0JE_-I%HyV>5g8E z1`(&Nr~>)37@uCcPBKY?$1PKlz<(DpL5U!`0lnYgcoKS8v+{L!ZYRM9oCTUZre%%e07477lRsiiT3ejNhmKTFFmwoqM(T@p zY~5MCO$rI{gtV@u;6}m8B~l>Q?U&vPXSXcS%gg9Wrd874Vg0v1d4B#}cZuC9YJ!}w zrL*Qs&xuf4(bT>Q=Qbl9WK0>4#CXC444Q?Bz1w)OJ3ZHW)p>Cmp@lZbCs$kE@l%zu{;!rw9*zQf)7%N31P9LYpcd2fg7i~ zy(RUnW5?Yv(!dyf9uY-epMf88Q~3u5) zwed$$-g3h#+Q&^2EIrD=DEp*pDV@cO<2v4R(|nE|-7PYs?=kj0ATa2r4zzRR0&Lgz z;VYrVMMVGm%FW9fqrub=SQrtTjIxnral+A$8^1sx+Wxr9=XPiS#_Dio5e^%p-40Y+ zbf3FJ?R9nCl8-bKas0P%))zc|SIWTE`Zgn<0qt((Zr5wi4L#sbR9cHV%SBUbad-Wc z)vH#C?i5vEOzcv2BCkwRqGPlmsf`feZHtaxdnB1y+YSnuR^s!9;h9PCVHK_y=wTse zO^Q-%%PuB=s_zQucK1{fpC>=AmV)R9iED@E*or1yOb$@kl9V@dzVCq}M?A1MCeLft z;FrN$lYg#DAO?|TL!wDVBT?}=CwlN>aSZRzN!JF``%O97kwFEd6T9&sq8A@e z9oHvRW=u5rWs7m9>wWa1h>mVuv`&+P4Zp>qHxqeAs_)nQh+CTq zKW6UFb>g_b^iIj@oEi>=oR|Pj7iN_pVq;#&PLGI)h?J(c+m~CNkz@_`29(4s=^}Fl@gM!2k20^>O!`VLJgMWCX4!_XxKSBO;Hw@^F5E*H|YEeLgC3fe*+z;by zqonQDa;KzVmFQU0;_*V4cd}m%BzrLV{q3elly}WA-b9CkU02)1B|c|8ol7D&z1$;2 zWcX+m@rV60Tz`A`!s)H~-06$gfi=j8z~v{^cIqVF+g@wew@;k!G4YMeE-vTn1#4w- z=GQw$(8R&XPuf)6v)iMZGGqyMW`5DHNnVd!3()9u;}-uLihuV;4T?YNe?jqs{%@lA z0j0f-d{6#UNgpUie`G-dlG9wj(_iu8$wGj6AN~0}5P^=r9I1hhRbK|yYF}?K<%$@$ zC`M)=|HRFh5A32^Ac6()DIiioSzMQ*efik*j{iwKPhKI50R^~_A_l*;Zrj#^D{XK^ zS$VlG=O~!zI2|y@m!&iR9l9?WV9$%Aw_ZeUHvyal?>2#l`rI4f3*NsQs(MACopq~S zpG@5F(5%?hgi4^Pon1+r3ysedORd~-<{to|8ciPjMAa;#D+dq=A6s{Dj8Xz{Xp9*^!JArn&> z3I6Cj$U)hLr6c*&rp^^-MyIs?4=6rsL{R)Y%d9ew3Z20mp9v7?AQd9f3ZU=1Hzb%( z876P=#O|~YJVC19UnC3H#wOYAU*ObKFgJ1D!-&WvyO?}Rn@M_lf57;NFict5T}C?g z>lc~m37Nv?b3>?RO;!tL{R6t4d&kN2DNWNx0~1C0BP zjEpwWJmS)(vy~Fat-||K(&Y4^{(76lJlu*>n?4%R7gy{E64nZmjDonbI-qdfzAn#6 zdU@_L;VEh0pPV`{+R*v{(2~qPl##)FLMt+{Rjv41ePLbU${EH#s=qGiI=IogUY8ZM z>ugPSbw7PWWnr&A$*0b{`_|jC#^bQ9c}~pOUJ?F;gZwVXUlCS1YYhD zTgd+zHrQ28QHge`*n=YYK)3O+;ITCjx-FIE4t-m&Usp0L}Zd! zlkDR@PPlNh4U#}Q4U~dyI15C7?^=B&<&#sfiKV8k`^=C(WK@yY6tO2^vsM{8)cEmz z(^&}m1!(|+p^lRnWC~YxpPx=aA7wM9AMVZi zH{nAyTBP0$UvPD!h*5%WJh+@u<(y(R4KAZMRXmGfGor>}bI0@_F@S^v(ddiSmsUg2 zNa*_o^niaUF>_1EFS-wCy}4>B&Q$l(lK7=^D+cemi2~CP7?He>3V& zb=}=IZb8kEV;g0c@?Ze^U4I%%ekQ&7A3bP=>Xp%&#UWNVu+}!&lZu z_L;~6SP6PmIKW$;{YfLUB0WUS^9Jmokq9q|g2>-OUOZqC+~^MAO#tB9V@pb+a1auX zSBLg=Yq#;+WwgAo@-@8#2eLwearyS*!7TZ+*Dtf!B@P~eg-j!5cpJS6^5!I>$IoG_ z=j){5P_*C_lEh8!T=Z2Fej4@^C-O$?Y~%9)6-U=uTSx(}g$|yZ2PHicDKiYIgrmXM zqnB;5hwuaywB!6I_pJNw-8z^B6(=yL5sN_U)jf_RR5BeQDG+GXag3b~bUFZh4k!Xp z)Rk<#hD(O2uQl15j%YCvo9+j=IgQ8Li$CG!aAjmX%0YnXoS*!T*M z`B{EGhK?q{7Gd+Rv|-`c6x2O-e-35PFCW${Yu>o=jj%Zv7A{{dN|8lK8H8X3Ok}=R zBanX>2(wm={U`_6hm z%oZeznAliX3Rk4tq!lhgF}3f`Vtz?QxUr(3t)r9EIF)M>QiJ_&ii3DZp_fNDlCG8ecC&|6c}DKv5i zj~zQ}9LHxKgfOO|!wf#`H}K*Iwm3(lO{yLYb$v#G%XsL>AK>f%&08*XND3|VY3 z+Q-14pqb!)^0VmD`ZCBYRha`Jh|3}*F6H)Z_@wR(2I1u(kxqkNMhi}Ya>tGxt!UW{ ziI?X6O4tc)53h^37hV@6*%V||Iy&n3O3;mVR|$YTKL+^Rm!{C&9f$q4_3b-c3B6Se zLU=m;ESKm^b__X^;xLss5`qhF-?*`r9iR(PA&?*hpS<@Ey@PvZ);Vq1TruGCz&EZye5 zkLX!rVq+WKLUm}xfa!z8)$_wJ6i?-g+w7qyNaJpKRN1ao`WX9o6k6)oQY-mf-yAg{ za9nRzklu`nx5PM{M0kvH`XqWbU-~uAE?NoKM{{rnQI^aQsMXN$fqd%lCKnOXn>q~U z06Fz)gQkYLCPq+$@XSZ<71{|wVJW`n-_<#hF{V@ayD65?3}6PE(HW+XT+2u}aVTwV zuG!*#5SrR6*T1O{o5EZeL&aDEqGafp*M+D0G>ZGMa)Ou3d|n2cliFS$^yTBn&2WXN z&mOQ4w~-wSvDY*sl6pvI!i2=Uyv_s&C~IyQ&Id-FnsD{kIu^T)(o&t)PrS*Ei3_9w zVACfGHN}c&*J>#YB9=zkKkdv1@4jnSBG7>!a4d;ogX zSZtzOw}Y zHsyo=`P*p!iOgOeUjP7q<`hqP3@g9Nco~sRV?@}Ax*#z%H8Qp2GUtvP(~sD44}cFh zR2Bt0(ll;$g1Zsf^6*ik8b?suE*fPx%VOc~NE>JvfpDpCB`HDjwdl_kt_b~KP!y|L z7|@(B6XYY9wEu24Si@?@w2i?v&_vOoL4#`?j2}`bb|KTF5nRhPR%+d`@sU?J5E5(a zbxH}!OiSBJxB0=0Ky00D^pW+R_%WD*j>PM{ZGwFtwG**X(Wdug)*s8yP?K?xtzP*T z?hKEu+Wtxp%Q&r7gX6>jHM&(i>uJhmO=gb$0qN(CnmM1oN?gc%SHsGpIe_rjPE9`0 z^}wB)$&Vd|H3NuHie8;r01=X?a$=~bE zw)f}XO`&Il%(`7f8IN3doQ_NjzFq#VQ-|`XClHq;_|BO8?d`Y9(rDYvX2Kx>p@l>~ zZhvIR&IbJ9=Gpz~eOQxk?DF=#)!Y1yY#2#3)2#l!S~A9-Jh^gzG$)V5&wOM!N&r{M z<@M#N?A&oW=B%32p!^$VV>! z^|^=IqpB%hme{2eu?_PHSgG6LS0{FD=g-M?4K1@mQ!YX~g>KNYlE7V6)opg?xz$jt zhEDNGc~$G!v_GJ+u2H8>H!_mI8nTqRMo!k;EZyYt1wp2^BdW)P0$@DiZn%%c0LzNf z0!PeL?hQy{ZE6;NrZ1N)rW%1~(aW1{`r)u>+4@wAb+a@w-oc#9G-~9V^f9{g<{dS4 zVsSL28dUDk!L~kVu3l2cM{LFCBDYe0v55HFG3 zaz@vs^;5WFmnSC$*1Ye_-}>}%MfXVd7~g6$S%jv6$6`z4zP-Ehm44p?P>rW2sUXr( z(UMmi&!u>dI%*vCdNc`fwCpEV+3V@cI)|}dfuVrYPqbo$;B!#EdU|#>vuz~kk8;sC zYWsgIr&jTtDXosNnOPlkw+BJk@s4^nm%imr;uI^zt#-JnVo zgWtRXCVk&$jaD$We6biZ&`WRAQ5gri{-MBoL8Dgo;|C2)nmwN8P7qscws1+pNQqm6 zF*iJJP&Juv%JFi8G7+=|BHq_@2|}`NR9Aq4Fjq1_8kIf<}%d^USJSt2?FQD|F4rVq2sh_i{aPV2=fE#I75snf_cj%Rx(XpXX{3TnoE zFG1$imPEmQq+!d)V3R}@)KDQgj9dyNf;9xmhbUf%lStO=Ke9su=HW?0Z==Ft53G;-ASLU9o;uV@MsGM&{b`;@|_WOs^u^sQH zrWTR+tu-=}okU1neNZWx7K}aZ<242AT{|e6vtJf1PnVSIQxT5Vdmd9YiH;O)M1FpL zs`-;cbhU#Vpr8sbJaW30;-QYzr7%Hj2MtnLQFhdCg!4Z(FQ+`k=oxUc*tU^_MdPMT zjk1RL3=>@as#e5t|y zdFK~51Ub{79oMV#SDU+b{m)jm#O+Zhs77R^V$?$Ly}sL$s`;>4qO(%g&M7-thoZ z0PALsS+F&fBPEU1F7=H2Gjd3hX>ePOv$q$YZ`(pYjp#Z_i3hmf=IN>Lk-5P8zc;vA zbY7C-hU%yt7EtEBOhD=+QJ&}`dwG2uoT8;+@f2IzggqTYR?VBG^;?qix8BxXCL=*m zx_aN0n-bABTG2)5UPgeoDXw8}HYX>Iz?nS8}h&hZgNnUkDA+M^M$PY>-b3lp*9LN+8)-z)? zE@c|;^+%Gl4IMCEE=dicf>(?MOh?DD4O!wi&<+_P_o%~Go1_Hlc5!Mbq~qpK{Q1P8 zC8fQlrAuXIHaY10re2?5|Ib6)jHg)TP1olD6fPNdQ4PbZ@=GJd}>eSL#OrY9|F$(Z0^5ia+*x25|Lmu&NW@ij*uX)!1~Y*OO%N9!fL-*{+H}mF4rbSF)H}4aeHatW zvamwG{qpteNqiuuXu=;r7>OVVgo?;|s(M|7rJxB8<_D>$lz#Yt#IHBF5zRGnjsr-ExQ_TsB%oO*AMC3-sQg{- z5gz>n9UYE{Pw1N)7qzpv_lDy-O0$f=UcY{Qgkxtv%wfxWb{z3LU4TB{Vhtk6SU55z zC8wV)Z~O2!Ffl>vp1OFuSJ`u1H4TI$#czxxl`Yw@2uMr%Yoos7{RX|xdfd2CBYA=} zF>Wc4m3_yI@e{8vYfc^`9hFIFeAAl*q>tnCUsICJBzw_-5w+5=0F6@3+i%mRWolZ* z-N%m)%d->&fEXDuUPCa6zm}y3zTI7f<2boldbTdN7&##c`tQ zGMn)4;?RiOh-Zc~Pg#S;>(jkqPrr9BoCd+S3xFgR?bMlzZtfD<$(_}J*Tax99*-%4 z6fe|h+WsfRC(a1QDNl}6j!IFsC_X*nxPj+k19-z(Z!|Q_6ZS>)eRClw?3?0p$c4kp z985;i51}h*N&!0Q>!0$okJv6-wwuDYv8Blshd0}2oSY!x-0(b7_)$c!pv~=em1qEf zF2mx6AWblRa=^0SZrr^)b@*1(60Pcr=71WhG|V7(75qNpr-k}Z^Ql1a`L6oh@>*8W_hL}kVGytSwWjHON;+W>bmmHHYapA*y!R6Blfe(rq z73m0?n3AT~}CDKHGvV||C_mat9M@KuIPvsEXy61k{sF|EiG6o4KL=ud(;@6Ayw=qzf0Z7KX5 zw;cmfrdsgCVS7ds4)_5Fslnlapb<@_*4{nEhjV+$)U!f^zGw5)a(z(Wp#qrkBO?x; zvx{_SXZdiq5u~&r{4>|w#Cwtb_$lB_d~oaY%Skex{B<2q0|)Snn$J}u`q?k8Kx)rJ zBN7t1#K-Cg&I&s0y8X$M*-fYp1ihekz@Al$Hgf|B`^?X%C$Pdep0ZoVCc(8nAPy?lqD_mGUE(1@CEZmz9P9<$vhl! zA%VDS`^lXaa==~GYJB4Ubp8t8&$7v@dxS4fMfoxNO+)weFS8zPc*;?)xOT=UR6sQ_ z9ocaTNx%0BE*s;#qy)BEnvoVnlF(5p$k}l^+q=?-%N+oodosMt@!mJvNB3r#y!E^( z^Is67$KHPt5&yZp>{cj+@x2aQN0UcptG1a!vQEQw6Jm>PPJ*9PRy9#cM3^@SZ7!~z z5WULXk%x>{&r|Za*;NH~q38ztx4CiQg6G4R( z>N#c(<^UM~1H-uZUkF6jiW?nfEU18bgxT6NCEN08rpBh?*RN0THlm6vg75p$>m@#I zo+9}mA0jsWXk5Qp$7?jv`89rtG5#E`Y3tuRa0;9qcF4vd%8eb+*EGEW#g{vcn`z_U zslQr5met{MSiz*1w~r(105~ZWaAgb^&^xStwYtiA^oFnJu8V}_1D9)K%UDT6r1&0V z@>Zf}s=hs~RzZRe*qk^tusFhH5Ft(4{;q^XjWU=;7)IUy0YrrM%YN!q*oj2K`k*w9 zg?{U{rFeRJ{uKo!(SO&{HlEp|---Q+b5!iu3MT5+Ms=ry@e0s%+mMuEvzR5jHN>qd z>542=4#nC^-NuZG&$yHD>hu@xI@R~b*EOkqtm-4<(Yoa<-FN(WMCmi%?b$5x|Ac@H zC+`mtp3&J-4Wsb|cMDdLNC0Qt2GfCHI@Fol;>zzGFPEp!l};0(8d0o!fz&Xf1Y801 zCBLEHvrvOy7+%>CiE=%qZjia~A%<7NQ>yL{NqVd`8Pc&cML0_P=`mgEIj-L{jkHIZ z!3!R00g;*LqD)$(cxLIicQWNhDrt6B(~KAI-#7QstB1BJt~_Hd75$CX3!L6y!4zzW zU2`24oG$b580Vn~9BL_us!U|lO94;#>G6$~A*rMFHU1ut@EH57$R`Ifxf7ROt2Xb_ z6RIk0WeP9?3#ufE#bMIhiO=a7s0+vTXz4FHs*4weq>^AODk1a$i76?~VW+q5*m3Kr zO&5zWrws%MQ&a+maNW?^oJ$^h_tilBurlZa1cU2EacmQx(()PevBNU1O~e+I@Y(~s zLr+bHaMKz1RZJBiu@k;!r}wllZP>eNDlwDZR_(!ISRXw zWS3~1UHK}d^82j9``lYFl&9ltjx8h*uC|QPlmA{8n2uZlLf~%{4dD(yYCbNv*dZ}T zwEZU;Uz$!=d320(bm|)LXVoGM7y|O+Cuww?aQpH8)1PsV82=Nn=$Dgr&sSJ=Npn1W z*d5?0dUm{oP%^MW*z3#@o9K<5H69&Jd3xlEqLV}Vm2m$PdX1l+om1exD8qaxRY7f%U>X$jvk5RTR&d=3W;&fdJYjqeLQF?XTbyvsGQrN}ZADaUEH zO)nWctj>jgSMQ`9O1PBa8;{$e{mtT(tE#H{cT@s%*mCQ5C3wQ*l8ET_ozXFi4i!vl z#M96QMZTvqG;;COh z3)aBbf&CtEzqfC{PoQ!3v6gq2dIt8bff8!|NNscVpT~lVT2vh}S>8(AqM z5fFWm#vSFDO9QdZP&M7L-R?+}S$y=gcYp`qs_zu60?o7;*@PbvHZFW^Y7tRVgecga zdM8lBMS~3-ST+4)R9a?wM$n<_%FY!uIFhUmr0v@*Fw1I{S;(AC^gWv2Ka7`t`tf7s zzqTMz+np5pN48>Iu4iJB`Krkg-iq_`a9$=%Bj7a2<%Vy>h(}C(=;qU=S8;IQGHVJZ zo?>+0qt8}8%LChAc^x`ijr3!pjg2bBfSa_(FbZ;Pxlbx7rPx4+>_%a$VeyD3^4KF) zHDXOK%tQmc<@!NPB>XAt1L(98L8UY@5{>&B8WP}>Fd18yP5S8X_QN<(wu_d#ssR=f#8D@e3X!ePJ90tDNXyH_u+a+y)C8(y_M+ z4>l2VFs%h{?`t@e`*qZEC~l2vjISf=q%Hsgv}r8`t>3v7`P!dKo`?}z+*k}%R-Cw> z;I!6u8J{OEMS)YH46f(q&VTJunO(W89W|OLxj`%WMFi#;#?R+prrAH#Z_XCF26PM8 zY3=dXHLc#)&Z7PQpxzY z5SvFTGaNzmhf-P7#t1JZCuga;dYil}>zdQjwoS@nn}_BkJ(zBG;&WU}j7E$nmI3#& zDqu}letfQrvn~u(jHtds@FMX{NvKRyMTVx#Cx8v{Z(0aYNQML3fWvnkz1 zH}!Nwi*!Q5zkp$0Q#b-M2M@kK^q}|Y&vE9scP!SXq?G6=+aG)FHw_BTI( zRq}!BfhzXcFqG5ca?Fnf&e8Ty_b^RZRDKX=)HO1xffSN$>a?LZw>4~ag298x(j;52 z26+6AWKwzLnm$Omgi@$!@1pH&SH;1^3AXnEzJEMzJK&Z06}ot-%g9JTE2s+T)p=lq zm(0H$tNJ(0J5BOU4mD9{l7J$#7i({aj!MWS`{L)t#i~agh7BE>M9JiqV5Mhl+-BOb z(K`uDJi!g{*Q7&{ae7@S1TK61FtD*}aPw#xyUeajKeKgE#^5z;j^)jeZ4IEI&8r0L zjTrWWtt71|pJ{Wu?2DV}`Y9fK4WE*7z`Tv-2phmX6JeXMByOA3L(HyXwGN!w@I+N4 z`q5T0=1Wd9(AXP?-?DUss2@YQ20sl&kir zM@91ahmE)xt7}PEG$>=h;1FL*sZ%jL26Q2AUr;W9ud8}=h4%Cs%`q+y$Thfeh;KzL z)Rw1Tnq>0OrG+%Vc>es%$p?IV#E8Tk#W{{>VH(Xfl&*s%`hxCu8yd=U;r)O1vr);R zMOg_U9{cyt2>+7ql6n|Sme{k9PnHf()8DFb#pgfe%&hZajqN~ae;(X;0?!C)s0DW< zt|;p8uwg&==| zN#FmK-S78D_G~SwjPCiTkD0{i9wn+&)#FCT!_UIH56ek#=|Ehd!j;2~@Dy$Z!$~}x zkl*>9qh#QRYw)JAqn*F=wb~o)?8-BrW5M4#Glap8-GrG{7`*ohxx?*(m+Tgw|dVtbkE@CSPJLkmK9zsKx|)O@jRZP_PXw;kAT2|L`r#yIPr~O~)NLb0@Bt#*KrDd&dtw zlzI1V=zXWakm5JPTD3Z08aet~f`26*FbO6{%#lwez=V&>VfPO&=)xCF_=ZMO*|r%~ zt|jjY?fx@tBnx9vU9f0GIa&e{lq7t8-dJI9yw6t#+k~9*A><3*cQZ5LWwbDG zr!X-*C162`Sr_#vaQ)@MGIRCsnogDTgG5`i@oRp4Dj5keP<2V2J@?+9e-32&xxoMD z&b1(YNAx+|1x~4V9#4Hm-8g*XcPY0~gD?cklGQv8;0{z#jvEB~+djdN$;k)ms!%}j ze|>l5y>HLx?Md3yCNL>7@CVjov$nsWB9D?o-^D%Lx4lw-fOmJCeLz!C_kSRMq&4dO zGCZ`3tL!=Fn^ zq!0x-&x*Q?vzfOy?m%Tat*Z>Mz$qq)ET|zGx%f|;I}Bc$d2X;H=)X@;qKbI%fH@ca zvA@xaw;_H};mYe@#3Mj#nCOxN+AAAe5MNSlWM<91HVejEEP`I>JbJFhy!Zdm0yv5{ zN`?_}r-=kBw_e$qQ4#8={5KBy4-IQ<@i0g?!bF;IC(`fAs6rVNv3vI~4?c}J-M4+s z{Tnvo^c90!`u@{T|LCMlMgnS@WhaX;YZ^UtBijs*XaiW?OR5>}P=i#%8_>`DHgg-4 zk@!y{J++_YLc{4LWQ4a&dH6@%`Ss;C5(ob{!NocBc;=%LIp}@MR9=nS zaftugh}MvjMFUweQG-#5T;BL&q-*e(dunr|o1j+kd}X`SsQ^z4VySMf!I#!D#$}Fs zc+@@HO_#dB5JwiKp6T2}Of~vDrU#=Me#ZL_E1M0Ouk~Z^pwD{`czc_?cljMw=?_?* z1y(N9jJG6m1Q`rStHfQ-KEHVK$qG|*vk`26cwjUwvX3O8#Bs$u+asA(%WF>Dl#@nw z(r12t9+&*YR(|-VM*pS0-mNkA#S`1VS8nH3-sHgEda0(RRl91E|I1+envPZ4(Z6`? zn&$I=lW>>+ezySV!cIMxH}esW`$}DvGbKp5yPzSc!ycg^vhGojr@lKqB7ML}KR>^f zn5Ff1%(%-G8p0>f%99Q=`iNv``t*I-MF=Ql2zA?;>!^M>h{$@Te=Iw2W5r>17nc~p)Xnlv?h%%jBGyKF-47fNRIClTMrKpVgF^m z6V45E&sc04K|<2th;pSb9Junij$$lmmjs)@OhE~D5??oz*c(q5_#BZ-DxNV5 zaEo5A@!V6AZM5*3LWo>6rkwkdcsYIA_!7H*+d&Ft%p{K}<>2|zMa$!n>2D@w7xp`8)4G1rtV#zk+{^=bj6bvMxo1HcQ zVPC?QJ!|IpKnKX00#EMFY*X|>*U&(T3rw`*kfRcF2NbJNAf~iJy(ptlRJ7^C`OukV zdThdr((>|~0(IfnG3WW*OLOFMUkdFmGptY-D-@h;jI5qCX_71cCos6I*8#ensQyMV zmv=A3sX53ZJG|l0hdNdB$R~igTL@^`MJ54ySslFU5Cw?_6Vwv7# zO-l8Ue}RVSOpf6M0Ib*Nu^~Kl)vA!7Aw? z@-F_LsL0~~jVUaiucz_<}B!DHLQ}Y?8UM(AL%i_g~1xD`zV%XnNi|DdYe~M3$AXNc8=1r9({z z@GyK`r&1yd?9#ZB<&AX6BgAHHnjkYNw9samK0Ckc;j6 zY0;n1Sg9`2`j+t5`=|Ld!}(W*u0r6gk#t2&@BXbO3t7z--R zxh2*Og@jfAyCnBx`$wdY5Q&fMMIKjaTWjN76jU0@s{b!cwE*rsv)ju;LXxB~i z7NXLm{QJ_zBR?zh;`+@OKym7|9hP#xehLcDiR75Tn@F)F3E8j%;%9_u44u}5%Yt7} zM~|ay+tLyXsRyi?k0DP+&2(7q*uD6-r~e|+g&D5od~4sK!wWWSVx0g=XV&YNd3JIK zrKF!Ro{k;@ozrHX`PL#KWkmhOj^~GbeS0B=P*Mrz;5u4JSJekuDW7HRnj*=J7J)t^ zwYS!5stpzf*foP8V5}sHy4i=VzLme}eRR%Qs%fYtqvD~12TK!0QFqxVz2D?J%`B%&we zV^S@Dl*yV9m$YPIfC3=i7ornNSI`sAD48B*Ve#T>ZttdEYTkGE6LWyi$k5pMIrCD{ zP`4`07`CaU(!nW#$)ThdTz6`%$lLhMPR<@?yp5AC3JqniA00VuB7IHM1ImExkSn<+ z{}|{1QJ4Ic|AWMK zA~&EA8S`8oPOtcT-RzXPPrp~diIL;0QxJukWJ00LDi-+|%S2pc@>n2LKe+f&T2-}i zuv|6FO?!XXa{vEBSX z9yA{HtMLw)c1g{QMwd`W zBA>r^-LOEFotn`)+@?nV>CheuZ}rm)w~rZcc$1N4dTIdO^>=Qg{xjS1LQEEfX8+S9 z`8GY^<8OWlY%$#^bPu`+q=eJ>04i`#*OJ*5#OlyKBxZ@v;H?1<@UDn zS;;;7Z(3DPtx2!nn=+DJAR~|rM0RVCex!ASNtwzRh6d7@vO6FxR*>7NzvBQL&ZtR+pLOZ zavJsP_Xqi65(z4yXfQt%hvFXR;*!wTrn=uZ{Ff`!v>KlTh3oA1Z%B;3PET*^@(zAj zf#R>WC|d39BTDPnRp=cX-3|lc>`Tl2dim1ahq-Z52{r&m5?a0<9DtpsfWXk-5fWfD zU}V}q`+|{sDGX$e06NfR`TW(l>8sJT2$Tzosg!pW2Nt!PxC{oO*%IIpTWQ*gQ~H-+ zGT=2xW3#?kMO#CRX??O$L|F@a(JPM8Wt*|NE4ngxvY-q+F7#k95h$yAnnI%TwrI2a zXAj^b@*M(%dHKqfOsC!M0vfRcqgEI;we_ko^svJPxBPESfLt|n!xTTF&?M@`w;A?O zvqn%~G6x6$SUn%T?bH|M*ySEGl3Bt$V14knN-m)Y_c0nsVaId?ppR#u{5I)I|2uV) zu&;NoUiDb#lHd;!1@O_e<5X@UIvi?g4y8z@@(dp}D%7j3e+PWd#2SD7^KF(Yg+PT!&dqON+x6 z5ah!_%r9i1Xun$KQ4(0$YWeMXa?$!^sS|6>C|RWTR5)&5z%jOPPlg{j2afLpZZiL~OzsMvZfEvX!mK)b=TdHf3gb{CqR=!{Ffo*aUsJcmLGlbB=T-`InQy9@$BY&(|M%SZGtmXQ<2(-IX^2TCYJn6u=$NkV# zCAn9;0lj3ly^Q>zpA5vADLHDM?KO4@X{(}={I`b7NxUWr#LGJG1|ayF+T;FBtRYhgZ_`ShdOFr+82`KHo4$q*HKoXHSVGPzzyM|@^6SFX&0 z#8*;6O@e)tbFW7mk0Q`R38bS)c!cWDcZlV*_;Qmc=a)1tr|mI*8qWla*6rHOvAlW= z!7NHEmd9S|)IP(8dAqw~b{R`V+zJ2jJ03DxYMPD?x9rPj&&DDa4E+7~mNWabZr!5A zSj3)o7w5Cy1JP>ln;9Y@fw2HM>_*5qQAkXwsLsApcKOViAJs3^>b2`J4yLn33*D(V zYxVD`-+zkU8qN{Ui?2M}^_SqLK_YN95Gy_}G+_&$G9=@~;yz|Y~_)w1nUvei|!f}dD z82L;=r(N#1tK*;?k8P@Ql0^lf)^B7mttaYG3ocrv)&{^$ zOOW*e0trtjGfZgEEIGCe&(8CKyCzvo$`l2fJdU(TAbS=alE@wy#rw>z|1D>AN@|?b zY9uDmkr%9YEnAtXb_e}&!$yq;+p)mn=fpq|!Iiy2@ma`YDWIQn+qhsO;_I>3PhY@L zVRXiD5e;ilNbJq1yVtL8rtMq7)CUDz`)T9w_KLluOB*2CGdw+gGwZ%phYoj3|nwUt$F=mGbJ`@&bG#1x@fgsH{h^Acsw`k-G0sZ=q`kWY}(x) zOEOztMxsL;Tjj=Tz!LB*5dhzR0O0T>Y3-Fa-aS-Rlb7vUF(YLFIM!04Imyh}CRzwe z6XT7H`k~;lAKEm_O8xn>XV(z7c-UnEbNXO2uk~-MqQAh$n+3De7feAXO z{*Wb>ma7p!%la@i_01YX3hgPf(wDAei~8L3LfZ2>VW<0~B8qFTbq#vPzMn8MGi=Tc zdPTd+4Xgb;+}(4=Os&=*gWdzl8)Csd#KZ(oH=lKg{3at<1{K9t^jd5wReJvND7fsuusLrGn3=&(P>m@f#U66*A-G zc55QrRM+TPS@nS*kT?*u^uMZpDK8IX5(GMc+>0fTBP9z3>eO`El{1DRiC9;^;@9}f zM~Zr=Ime$u;OJlK)jN;hjDq$S;OFKo+uAg0SvmLpb!zE9pBJ-o=ggxgU&<#L7&{SZ zec|c_OV)4+n}h8Du^;(t6k+DadHw5poj7;*gU1*YV_p2Rgo`CD(qbY$gg$pU?x!lvnXD0*}|RN4p=>mDP6Ej_a+RTYRl>c zhucqL6KU66ctL&R(YY_g6^S--D|T|@2(x?C5PF4&ZkBtLA;D$TUbf1Db}Vn1ctU~L z3th~~)Y}}?`m-E7Y%^)d^mkeS4~5K*3IpIcN ziKR#)|6u=t0~V@XFpnUe6kv(_b>ERAcL9MYSdJLI+s`u4dKY@C4A1Vf{S!M6np^!4 z{;*@GPVnQ+P?7`%zn4`+ZfMS@U7oa|DtjxqT1JorQvLOo7Fyn+cC7e*WsXhi)!_>0 z$qqnL5;V;(nWsZNtW7qBm9-{sWB(FaNTyM{sH{ydT5YCT!_OIH zlGi%(?2(AuAIr*4B9LM6`y9JH3SNL^c9XP{$*hD%^EZ(eFq&i+uF~!M_O-wQblNEN zko9~^4r$8Jh17G8A{HD+Sv{C)6nG=t;fRjTOU*?^8$yhsIFIxXS06q4C}-gz$9Yy( zr?Xa46Eauq5L;mG`o2m^F`k^$We>(T_gbgCq!=`D5hXJ7XI@6%qBEa$b)yS!VLXt} zyE)5JMwc})7*pO_E#a$q%)IK276X;h?!V+F!1{73?uL?5MVhL|)51%y=HKi@xj)k5 zjl;Ti&Fe%TTr)3b&zhlD4_s;3(+WXeszaXs)?GzqiInkzaMo`$A^%m%aRV@l$U^EA z*{PwuHz3Iwsz1sMktAyOU_P`jZ!5nXfv=QaTS6AOyU`roV!|39z`=D^Dk{}!V9?1w zw5pRGPL;7iSXx}Hou`JfTIHX{kVWEHnn4@aa&J_|B+HnD!9BZnbw&N;ZHWm({xR46 zlD>5tdxw8sM(9os2I1hJ*`B{o`}tiW+xH|Hx#mkXri?@i$UlGB99*;O=NG2;DQf-m z3qxl-?ECWzjZdCpwxRqJHsRmCVN3)GsT7sZ28X_9Q&9V-ou1Jh@S@gC)1_(a!*SfaM-XOJTF_|RPd`!`Wan_d2q*z#)nsVQ;(13 zKT#Siq1S42yltyiH)x*2mFH|eU-hMUd2Z!uO8)Dt|GR?%YS+Axm&Y*ssI3iUQvn$F zDSHEw?8V1+!3ASz512WkSO7`{{pR54K5EpJKZe%=n$SC5r*>`N*&c%irM_*CtU^*j z|IGe~YX8N%clX;a*f8VtTiW5pcYg1=WNm-j3eFM7*Zw<_M~N-$7TCz?c`@g$pK>~q zLfe|+6lTJMHILjPkyC&N+b7xp&}AoiDQShgQK=v3d~T22nb1*|%W*BWowx ziHR3M0?LVt)3d-b1qK4+S!ej=_+)^7uz&&Y2Zm|ae1bW%DA_dZWM5E04trv9azaz8 zCA;$B!0})laoY5TS@;;yV7!#QMSVoJrk8S|KH)cD@_tZRq((fUNS%988Wy*KYkeC@uxz# zpt-W_J>P9Tht&aJ-(*ZZ(tv(tQpWo}K@`2n|G%q%8O=@NND;p?myO_WA}Duu{x&M1 z{;<0B>mP}d+_|{V*|tF`^e(?FMEDTo!kMFL^nI8MQ4oe9GbLK=cOM_8%*eYxCjRv} z5bp-vgOjETy5MqYnu#r|L^=)%p3z`$@-MY*y5UARzN)G(SG|kx60@f&ntJ&c7A%NQ z(J*ZGegZeh=GX@8vU6qLVt{Y-L);27)dZa2e!sp^hTJ7Q*M6T5qfXq%dxh%x6LKmE zjp0-mKQb~fvb927ji>3AFpnYq2za6HWB{=qEh`VB2_MfDyZNFDgAvCX{~&CRWU5*i zCvd*Za^l!?EbuZBw1|lE!JwNY%k1WW_Gx)|uBY;#Eldxh^qR^>@aUM^e=5D2|IENC z{pLpR=8Stm?@r5z-eWYvqeK|`PhWsx_hO0l-?-`kZwS~nq@FN;E1gikNflhO{#sf%YN;iT=4)Ns2iS+9<4TDxL}qR$$GDXp}m7^^7Ms=h-V zLP}N7Zr$?tJpX|q#47t@UoJ+VToDajD1Bb}8FEE-7q0~e4#jLD3r@fA(4&-U+^Dt^ z=*o_>$vmsiY)oAC8eR+Vv?0TI$X)}-Cu;gvPGU=LPn(W#F+d&ckvGh3Kgyz z*XeaDT@(uC(UJ?`Dg`xRW=}i)a9$nJR}RJf-|{eaiTO-IC#XbE(TG5{batgimCZ{7 z-tVkE9}s2}QZbDd$MC>HENFF>po5nd0nNvu$_-Qd&AYshLWHs6)3^#lCZ+%!--l4* zKc0aMF?>o21OI~Yhvchc^5t8d*o(i4nf zB3Iw(>HgaO=SLN_Qb5*q>)UrHIPC~uEEIa74$4Gp)reOFert461KhyicagC%Y&w`(z=?C z24y&>1KU|DJtn?A2sKf|OR85uwIU@5>M9AtVnwkcW%4Onh+~L5bJzNYvmUu%3qYcR zG|ql8FDcHQS#x!LiRU;GU2y9SsdQvR!)Mt(Jk^lef|6yZ9EGU}_i>^^dn~!VuUpWIwq)1SKgcSk z+xUYJf5!bjdOq8K;k`hhDS&6Gfq?O!?Adk5OIbrwt{j9g&X>h!hZ_#i4 zdEW_?|L*9Gt};58%QT-48jO)+{9Kk^y{R(m557eRN} zsFc`@^a#po)3dxxi`e)=PW*fsay{4OOhuB|S_&B;7n(Awt+g=heHVZFL` zz4km>v-Ea%j+vSM+I3Y;&g!8MtmgQg>TosrMy|nEDUBk}Q?ws(`CMB1oDyW+yyHA4 z4m|t=xem`OD40HSkNkf0=$}*7;{N~uu+BOks9Q)J=XOMGwN{}1?CkPs#s#%~UaCfe ze^k(U-(o~2V4_0u&XV?aNg=Vr;Yo<&rP7ZdMV7!%*}?NcCOt+*O+cWC4G}ZOuy5y= ztG8ddVuj2N)An$$x^|W1W%Z z$}{|LuUWtT`0;~X+7wAMK)x#s!)lPmw1bbHVs;N6yJq2X#`>7&B%_lJR z?EF#eacP7byNuhmMeWp~X~An&uRh5VG^B&1B~3%8#*#IB>HTo7(b;)fpI$yXvfvL} zdW*%QDQM{4Jh;hxKNr4wb)N3Wk|ZqlG&{TEXU=pOSv za>Vv?78{*Kh=gso%HA(!W!*=Nh`D`U>#R$h9}elwJo}G`)DBPZWBBd+*WL6FHEQ16 zl0G}GvN+T&qxYd8gPeIU8h=1KUP==I_;JhmeZ0x@7!H%AE++s!2oY?PrMCQ6pgW8Z z+|fO?w4Sax9%>k3zP2iSllLXttvxg2j(lxPjMrFBZ2fPXsA4j3!nPVRGjNwKNWz6) zJlv(6zE>=$A`{`$pCmh4I(D;Y&>w!Wz6Mk<6Fe zoB=ZcjI|36eV-@SD2Hw-AyxTr-~LHSiV6Bcafg7yK_Vh*9Ydj>c{ ztXb{4@AEkqHiYCwy)G;iO0XUGF9%;CG6k~3J!#DzUfoo!oz|*y=?|#wu*SB1A&H1B0#5uq7`@Qe; z-p~Eq&;5uQs)HOuK;PO-5aEBw`Qr~`c6Sx1vvX8llKvvTdD5LXa*JPvtUC?fU7*t- z3h&1m0q@I=myru18RCT$l%(_6Eu^$5!kt&QObat}(hV?`2oq_Vo-#lPeFAV7Ewq@N zoZKBS&^e5WPw)%B4g8*gvk`|kG#MuF6>^#8eF#}98Ty{N3vNzZhqp+#Ea+I{zX(1; z%t!ht1D_(?t49dqTX&21qZL_|P%a2(k<&wvkGwBh!xb`oMG2>YDfo!{FzFYGP+Y8_ zcLmMO0Ad|KaY7J%f^bekW_)sK=#=KcB}_0D1DnqyVf;0;R$p<oavZ2>;ciaEBcdk;N}8!@dT%3Sy>q)>GU3CMPo95;A1jin3O5punDeE z0Dw(r+QO^IEOrD(MwXQp;EZ`2zxz80-5eV$UJ1&rVk09oaDXw{!p&U?9IgXvGH?hG zZjy%wg|KDAG5ZHFk-1-fv5}Hx3;G#53u&o#a^g{&^ ziRaHYfh%uB^Ds%0z-173PR{0TLb*$wCtXtTiz0s_5hbV_1ZpR2PCo*KB&kl~z(@a- z8YU2GD9-MJ^+FuXI^vQ>?qUSII;t$t6Z=_pgY0}g2NupHUE@fBem?m8EW7S#tZRU| zBd{^S^M1k99uEcPnZo0pz#B(R58=ZlAso9sPc4eQt5^;EMgtNW?8w_sG;M$=Qla5* za>0Z1V6ZQAmT!`Oy^8{^d42T8kdAu0>EiVQr*M+s!B2v!1Fub-HsXJtLj5%mTVx9g zTM*j-Rqj{lbb*HQ^N8V+WWoDf5wLYepg81b`+~uD`vBbQcs#5Qj=S4q9ZILCw>F-@ z5G*wft<7YM^I=W0e6|_9V2Ujuq27r(WRR9XR9=UTT_aO6Ux8cy771U=b3+Rd_5It` z^Ps6PLC%}2zXm*{HV!7(mh1;agY(KL|51@JqR@cd0h;840pz2iDSQ5aAyhRe9Z|)u z&Q67I-fA{Ftfc0JmvTv>rCqLjJR!d23)e6>lnsW#(QuD-0ZcAG(=7ih&w#J+_lS#f z%5fIlACKACq(~*L5Gr&@xKS%Z7?7fwTOdW*j_3xKZ5NgLhPN5iEndfXtQn8kA$dNN z*j`@3)HO3TwaGa_3g385C4e2^UuW~Chib~k_2Re74VGGkq8$@;Nx(>>i~ zkIb^-SJ#rCsW`Xx=h=iMHJM_g${jnInlZKZ3o5cl-B^)Qc6AN+ZEP+pHhZ`_y|L74 z?KWKS)?1|Qq>nXQX*c+5A&3}0ax5~Mb0U;F~+1qa0I%OCva>-a9xjx z3|h7r$90~4Pl4N$yJr@Bo{V>;HE%QN1nnPu&CDn1PLsnAKOL)ZiQp~7|dTQ$| zY-NNoeG2uZOhWaKch^HxM1%7D-T`N8ddus|%0KT}MDM@>2`Jv%-|s9I$x-w)x2rFz zDY37g)l{6ht~55*;b2I~wSBhl3hV<;-(y7-8u25|@u^#YW!~W1^qmBBL4XP3KNG{j zfpkfwVO)oA%)%`&aCtdJfGuap{U)rTqF5dG?qU+nondjvYENG@H0;tY|0E1-8aRq%!YEvKprca_!-B0qQ3`eWfyfX4PAGy zqonWRtY;1ks35zIKp#4CNH%gJRPejsK?H}5EN2ng9X4=suHpEjX&=r-oMevZ(ZG>T zDqYyo(xJ6T77$h-Jgr3ba~xbl3a#eE7h;xe?FN>ULagg!C)GwtE%v8lOm%00kL}U# z-wzw!lRtN32sIr^beO`ZVB3M8P!2=CTqeX1!1!E6IImoX6BAr#S}jns+7sRq#_g|i zpK`!y&PK>9lyZ(*lGImvKV53`!?f#x<^H$jpTEfYDn93z1|P+i???yv&i2v*j+sb(U_=mY*^kV|>;i%OhVR(W=T+zfiMxhADlPw(}C@ z+_RFC&K-Ic+FTmrcnF3J=#X z@Z$GZNNy-p?Ypo={nM))jELRlj@rpFNK(;8vqMD07bF33=*=|2hPw&kfDM5cHOTU; zR5Z@!LHBtBJRMP{B41RCq_Pvm`#E%nP;K7+1C1cjZo@w!x7EfKZ0`=vh^Ma*=sR#J z9#gWkxriebtS(gsl{U*?R~&bYg}vcVxy2Nd(`>N_es3BkI3&DthgXca-@m?C?K zHyt+MnJoEX_+iZtgY427j;T&ljb@)IdA;+O_ZVL2cn!P;{$(P>SlsUXGu>=kcYi3d z>Bxhe(8q}P1j6+h^M5(NBj)2n?>z(7EjJ~5HN(G0}qi#UX0@ZMi$0F9mC z#e}6`k>ic>HcXj(Euv{Rz~t#Z^Urm&Xxt?q@ZhofZs|J1m(?GI?*<1t+~}*>R#jWW ziqVUZTF?h~MM@k{A)B+Xs-jS@f82bAlQO5X`qfs$8r#H_>T||yl}HfRgQ7qakt}^_J&W;F<+8ji({nkn$MdIOfWbwTw;+Kb)MQaDr4~{a#)UI|^m6UFdl#$d0OpMzi(h zjJr~@YudaXuc44YSz*t${Ex-!Z3?1~7ui16woB&l%J&F+Y9Rkr#}jaKN)+9ec3n>ceoXUI`ZYucrERg`bu8b;ge`HWxjXtPZ-4S zbzmmEFJty_`MaM0uJp(V29CK_=^`Z;PpM*&tpz?4RAQ&)sTKv zkQ((fb4Sdr&Pdhk4_1(q2@kKyTr=M^a7&o&X=@sL!lKi6Tt|h62ihi{XLmPxPdpMF zA%__RaeIkJJT?=Oz>TP>01LU|!@)@zVX45MEEIV`FTy4YMu`Rql5pLC;DL~pklT?` zCB#%gxLXq?oMKR?mVvjEMTHy;Jk_f4Ivz!Ml_!NWEcMNWWf+@;`YCyx_PKd86Ec|g zFgU8B=1S!AuD7+&^Xb`F{76vXP(Y@77(ZUmNDPvz*r(qYb52a$a`4o7YEPkN$AYNe z%a`ulX>m`O)Kvsw_OIY;j+1YVQJ{+h(MyVVa9UZON zJCuKxDO|z6mTNLmH=BZ~0`Wg)DHyuZz018Tzn42}09k{4>E|Y`)i-8?a)TX06FogW zlIi-V+fB7SZ9xfqzpA*MExud-RAg|*=B-;VwP#!r+tib&u3-X}#Vzz!2hS?xGj`mc zmzA4afl+0++o3MU`Z4)0Az%5EDq|H<{q>3;fG1kH0Tw1+K)wz-Lg zTs$~_BTlT@YWaClh^X4vw^D(Q$_A*iR+uu;ZaTK`QY{amhG(L8QT+Wr!{KKPr!ZKO^XBT+`XvS(?JLe7%4FpUS0>C9cfeYiX&SA^dE39Y3Oe KI918$>c0RAHHPj0 literal 0 HcmV?d00001 diff --git a/doc/images/plotjuggler_visualizing_data.png b/doc/images/plotjuggler_visualizing_data.png new file mode 100644 index 0000000000000000000000000000000000000000..a52732c442fa51b3d102e14115bc3d6e964a65db GIT binary patch literal 188273 zcmd43c_5VS7dKv_Wu%oPNh=|#gp55YCHstJ>>ZHs+0%&46SJ-a}R&)AlJ$@>02 zl?Qr4C%ThQ9pMsAzGL;_>9yw=q5BuvuN_ZPJzjb3YI5#0qk_@AIJMZY-f&iYG&V|{ zG3r-dc4NeFYIOCW^sH~QdtX$;#N9Nr?X0^LH*EZ0KMpr;wR#Xe#t|U`M?AfGv*FV2 z|N4S5d&ak!S|lr$XXV7}cgJpTVA*>3Uw?!zux^F6^~+h-{EtD*Z(H5k7}&IZeb0vf zJ>3lf`GSh%sD&vW@yq{vn*z-R>pZlec*sLlGS4|4nSWoKAB(1VIKX@P zacQ{tIo)qYak3~$Ye$cmTtOe4a?O&wl8vgd{lovc!r&?atR+DCJ>y}yQ7D;BQJ2K&&x@a@&Ml5ayYu3Z_c-GMzXaN;KgBrpE916py4R_^q(KH+^)uA$`v z6*(M6?!vUt_s>NuxkQ{RusuZ-5uqi;*6d!=tmg44Z4Y=k zi4<2MR(eT>?HpLaXrk@;OiNMBxET^K5inY_gk^!mCNl6pHzF2g%gLNeEj*T)lM9Dy^OsH;uw zx_9&47asrh{h#@Fyn5~bFMI&*UiVGQ=L6=@t*hHH5FBCQp(&XA`JT` zR~jmJy9vA{e&+nE6>ckD+j{cb^#?fDYw4?z3Th3SRX4Lb$X`i5-8;hQ)>kTDem*Tl z%JSO5(6q^|S^v!b{vw$t{2s?|{wV-Lr-~W)w$8i*64XmV-M_urHvo2 z#ZI}ELb)ZoQ$&`L5uxjRkMuV9n5Lg?i!Si|-863w-x z5(#g6Jo>SAua|?$Xus^*5xbkE<6~oza{+-K<|DcuX6x1-Iw6fZU76@s%Apd*W)Y+F zFS>J9NhrEE1G8X684Vf;qzYs{Xu3B$IiB*^FouEewjQ;~35xM2W%c{iUv64!3!~Xg zHgF?|J0>UA=$YBA+??6HyKB+YX8ed|k7JX9Qqr4$b1mWWtdXZo4$y;PrEA`54{&*x zC~cDX>MDcgF<$#PIropTgKhq)k@VRf(zBVutP`~B{8_r0EPvez=b{x)DUI^f+rNu` znEioI#GpECjFLWcjv(G9Mr(LppE-V^#?;a6iAs-%bs66mHU1^NB;OlH|HaU8!7QIB{Kh!pg)2-dodb`<%Ti(aSyrEVME|Vo6g^ zW_do;L%&mO!uAZc`heR=J|XU2NrgbNX#EEa$$eBvCd+nXy@ijxQdUUDXjz{Jg(@a& zCg)|9#djgiDT(7-MhLt)_k%zo`o>$S{-{9-XwWw3WKEj%_BpKb z9g_)ew>Zd+n6AL4_eeQ=iioFS-1X7u_-@&E(DR3ogmcSVu&l9Hzd(k=|9Zy5A*@ej zXs7mg)d)P7-9?XRE0N?XJN%O6uPb>tT$nl0tun4FNmyCuH(^r)4s<<#M|Szx8{+y? z+0SxdvX}KjAv|UvNIDd~-HhpZ>+rs;=CWK@k3eQ9As)4l(B*|M?@mj@noyyd(sqn`Js82@n_Mg@o+?ozx^ltXZ8>vf0Jlm;FnL7|Aah z^P7@^XE5<+aE=8hq=f=#>o`FKiu-3A$&C z9QEkpF6YlvGULl5Kp*7>%%9HIT}PSt$lgPT)p%gu#q`|!@YrbiUf)6^0ZVKa^zR-@ z%N9T9uU+qdBW6-|&-`1D43tmG8=r>fzx(Y=kZP_X0c&zk#h`Yn)WFPoyjMy?WF_O0 zOobIi8s&m)Y_ji|&cR?1FR`oZn)s&v_>Q}i4Lo1Qw?Y5Oh=JRn;%2t$SJZQN=--r( z$$5Lz9c90%@=-QH=5byX$2Ef_Z0@lT4FjvGSnW!Mo0Xb0^T%P!jbS#YZ9R9!-Doz6 zub=p=L@gh^W36zmHV%2V=jb7y=6BXvN!#wBlWE2t zn8FW|w784f)Pn`9r8^8qeA!NEO6IMuvqLp+$`3e9%2klw+o)WU88pkCz=R%QUbFwiI~t+HdE`l(oHLfylnI zCS&{|Lv@8%?EW}*3|*ZcZ$G^*uNaf8%7J3o z`;^l0?4ph%uSk}S=jol!Px;ciYkJOS*hO69&ix*>R^lh>JqPkzT-U=MTwCXha(R*G z6MyT?fzFdQDzi6p+Cmn)!$j%!9apl9)}#EdynC#D%*dHQNsHY( z>8m0x_*b{5dWB^^vE*C6+`4UGrtMtj!G)QMG|l?WX92WSys`JMLlrj!I6b>CYcF|G z`=AR;-+~O$Ulv}AqRN$byKN4r6Zq@ufp1!HzK6Y@;{EzW&Sb^_X4LyOQmA=Z@33c5 zcS}6_7JY~0a(o)T&78FD)AI|Qzd4B8ic4&;?(TEKUmngGk*e3PBlTr0JikQ5vSNoS z^$+g;YmDEeczAz6T7fc3p|dgC#HbDu|DyJ&=2SsrrDy@qr^`Ka{EOeHJ(4fcfzsU6 zKVW`Rn&SP8RP_Lx4r4)4|4XpMF>%TG278gPOFe?xL}a1Ls(ibWicQ)L`^W!l~f|(tk|yZyyy^ zSy-`0oOAvw6Wf}!8RTs3PTVgy{chdAKg*rtie#QW-2Z={B!InqNgv-&L!Z3%25zwbKm`#$^oH+2vo z*G-<@F#5X#`iHBAvu%Yc3s`RX{Ve|d`l@zd$(~niisk?N-~I~XHnLvacbK+4>LK6X zZ}$5)4=00L>#po@^82rQZ#4u@qnb;|EU7DTr{Cl_aDJ=H)NjI7n<7>Sbdhm6?RoRZ$A&VC)mPlojBq|I4$w<+s z$7mDO!YnkE)Y$Jk+qhqR|2eCBt8;Cdk`{07+;$bDZC9<{{D)WhhhzB!Kxr3jXgX(JaQqUaXw8Nu@@||$`=rGof>hnQ8?*6ZUXlnVgJK& zs(S)hw_uB1hI4nyFTIALyGUrGMaE8rZ)d!pI+o8z0(;b5dvO}wvjFZYiEKZ)DDlW+ zvd1vz#yjI(hDoZsxg(pRCF*ZB#qyBYF+;)Jy)$NB!(5&X2PBXNvm=dt%OrnZDNTiIXgFYYB<+G}qEiEQ3)at)Dk~fFL2XVSe z1Ijz)tibAe(3MPG8zm@U1JHzoXbmsK;^o$sK9L*;<`XAp%$4x;J+@XJ-b7I)(|Ng^N3G| z!bX@bUyQSEjP4-v;Rp55cP!bVjJdH-BaAi1bd0d6dt3pkv&89nz~4RFU%jUyf>YIr zJO;Nx%3Tfig$%@bkEhcfsIy@QFpF41^juB0#asLSGOtXeu98jEIqU0_j^!;W>b$!5 z(#%gEd@Dt3_sX^Uu*XtV8?(MN^XarP#~cPcrdGnmg$1f(X=G7JjdIA2V9S!zw=;~3 zbNS@F&)3Y9jT;hMyk;AvN)?x@w(vjfzZ_O_7nrx^fE(C2ZJgJAxMCs6@t6fe6d9*v zFw&^>U;EM_fRzpV!pyI@e5Qt%lAyeWG25)r7YkP}vaa8!FOi;ra|Ksk=(dShF?)s= zlCtkI|5W?fQ)zU0G~RJ_Wj=JRLRi+ZWK4kGo~~mE)w`Pl|>55{C+sa6xOw9Du0hA8o0hy66I9TEQO%Hy#9 z%S4@W_X}KZc#{kS)mynzVY+PgX-1;%>@0=eF5U4Jt`x7|!ZWbA8l>Uagk9p%8f0L-+lJdVz z{kGsP7jhIhhlP|^6yI;-gsj999s4}0@9mcK`fA0Xy?Sg+PT!Y>$G3Zj;}6+WNksNB z&TwHGY)R7U{VvAGP%&fcWV{l5s2D6lcJGma2Tc$zVT1LxRpOP$hZa6PRzO4u!+X84 z$e|T_RwV*A&Df0PHg*c&64I&mTU)m2+@aTjg*t$hZnl%*tqW$|>n5zFcdN|2iiI&4 zw6k{^#^dwh#EYT_twn)N#jc~#h%Kl-81@SN`N~~#Lc=rke-W~F0pUSSjH%M*Xi4;V zPpUUc-kW=dth}?Bl821J<8%Y8ldnY>Z!L7E>+#C_77@O-e?fG5D<$ALQZ?fp`2D{* zcU|`l(%^&9jU*lWd)cz7g^q<+p9yp)s)Qysa}O+Hf|_)auN8Y_pSbosTim9pD~wNO z0_)koO^x0If<+WXZk`VkGz@mr0f=FNM(Uex;DV`{CZ)YSsSq4+4sanE%bM-n)p(Zq z7{?0d#XwSlg-^Qk;r|%|1FZIKm8Na?@Pj~Ynquwn#~-3k(%MU&RuHX%79}#)ja;4U43= z{qseR=P}I_68H+GudsL!C5 zv6*#0Y#vDotha*vu!EH>K#~tVn~Q%=0is?V$p)y5Oo2NOKp zhp#OxbI$^1p;hD_>N{FiEdcpO`U2(5*&kE<<4U`>1}O#xHu1@LcE`M`QHfsze%WKZ zeQbYQLZbL~&k*Gw9x{9@n9rrboPWWNN#4w;MkP&WA8~vX=Ik7R=+qPT50-1qEshX& zPT;$6i=2Y_nvOaDDG#=@n)Qc^QYC>Q9W<;fuvi(f! zu!qIWjfHCiagsMCWJq7=C#rzQ`}s(RF9m1?HM!F%-5|W9K_oj8cfS$CcDi)p9BQDV z+{CGh?e*XMJveMh76I>gU3xMGX1khYa;Z&kcUzP{4J_6$3cgr75m&zhF~8>u%ORis z#1oS4Bcmk8^?=*dySY^=Cmt9Di_{@zSKK#EMMle(eGoWF%g{*=78P8&vLHhzjkewvoRvs=a`mzCj|a2##-#TfLR$Bo&{K+SF+EoOTIW~;m@9nIBIG%jR@&m{-lHB1_N`6FbOrK`csk@Exoh}5W<~G47reeEaU7EE z3Ogu$L(Y3HJHs&V?&O}md)?wpJZqX7WUXx~E})~n##l!^Ki1@x+<|iiIfh=E))5io zBB!zug|($uj18+^qgZZ|Po7Qlp%{5g2_Mw$y#^M_#dRUhy|Qd*wV&abl2%P#d{Ky< z?mTDHWY5OFFMnm8ZWMOVc|dHEI$!@ra(&uZ?_{TtPip@@k(aZu_njnE=joWUmUlml zf_=D;tF9ZwK07WEy?pGI+%9E)?mWJbye`q?oz&Mxg|*(kaF?~R6;Gd)7QG|!3eWla zA0u3H%>!6G>K}F1mKa@-{TQQ}eQ2##Rg26segNC-Hg0ay6qlnP61M%_^IyUK@NRIF z?!Q+1oC$uhT6z9?pnO>cG-7QXE0$B(i=l2bb5Wx;s^PhV$IdE^raRO&E?f?F6j>)q zJ~H0tnQU`LDK*m(z&(=3Bto}{&gKRgo%2~=uUWu2@=p77=UTf~^#d@^PWh6OW-dlukWz9@=99x?10a~I)hxR`}333PLHWx9?Qa0hPhqki~T4~ z*_k_hjj_#0O<_BvCBrLkKIhQdlhjhGh+I5}&xzFa4+|4i$L2*o`&XM6@4FwmKfkrc zVf4wp+raKuBXP5>p=wle6$U+sa_o7UCIM}}v}!HtJj50$qpx8!FG9b~=IYwL`FrLb zpvB}0xY!340Na)KS@n;Em&a&uG~S<7d&s9D*x>*;=YPji3#)*S14kFEEKmkCW?QTE~NI@oMYWWMxeHKfEFHP=E zv(64QM5iLDhyrBP#k%S+!Fb=+;DBVc7h&@4Mb4j$!||vYKIOaHbJR{3S5H+iruLih zpSKN%6A>NA_O#ur^Io$f-2mJTnd;9xB3xPb>E}W#JIa*Znz=#mFZYRE)LBdh`SC)l znpn4l<>|0RS&kmJd^^i^e>>H6Y5JkDTSIAXVbjL>BradV9{ve2 zV%=vQJ%_>jXE<;OzIJnspi^?Z;S*x{P{6v z7Dg4m%l32%ajK#rR=O?N@jed(8t=DaCt_N5YtG`$Za2UA4*i9CvC5(|QWd+AgCl(O z#R31qEBu&t*cjfqMTNV#(>YGo%b1r6;5k%{?QK@s*9UT|j7qLLXEwZZ@MGv2$i*fL z2mJEDGL}4`REKQ`)#iQoSARnH!(IS_KC6``@r+5ta(S*1r^BsIIF)@`sgd$T0hRf4cfu7KES+NNYWY zBlHoa9+So$gH*>#G(kVhqvLKurVJ1D{+>N{z)-O!-3GWj6ih3&<6#Z66)P`@AQj_Rc0+nfQ!nr-2aKQb?IcA!2#uNJ z=elrtW|e+S>Y~%3qmm76>`&>eTwn9?t+l#())UBA>kR#>CG$#EI3 zQ!%3X)V~lboNbb6K3zW7N>kJ$`c$qi7W?^qEImn+navn0!ME z>Y>1KT5q9aJUfKzl*nACmbGnFARG3+u+v^>Ad%LN!fVFMPnq(|-XixMgQp{R%se`F zCG3JHoQFP7r1LBIl??+p>s_eTw+*`2yRdub4;KwP4RSUYse3r_;R$K+Kitgm8?6<%&Ne;#>CGJ?6=rmzD~4i?@5f2awGxjjyly>`Uy*- zB*J)gi2Uj1x*Jnjj+UT%9VNHoi?KcHlAP8;m<%L(+he zIiT~NGsMDvmn<=pQsG-c9MCNs2RFX`m1}1D zMg!-p>xz)qv)s{Rt;u^2x(Uz0iYP=QDcyomiB98BEUJCtjTqpFPSaqxG~8TzYMhIO z(~Zl}P%hzqr?(uVtl0I{X@7Op?HZ}T^i%DaR*aq^W{#%qd7+yy zoJDDbeHr8Edj+gr`~|V7z6hV4T2gZ@yqc|)iugF*iH8%6;i)yieB&4G`Wy$$FTmE# zgER&{;nCT#K&yaR)V-Cd*JwecZJ!V9KJ=6M*QtDM=D*6-ejG4uwjz2NTaiYR56lh= z1!}C4vt36u7K1iz`Z@GhE*CI&6nE_sJgxlO*ZP##IuQX#wQ&Vg|5f+G9XR1{-$I1P z4*4xv6q2k#yi*@a_V?*1Dtp7{CJbwzKe^ORLdP&!VoH&-CAGvIRaSVtBUnT~(@n|d z#-@wwd+jtl`@K>Lw_xObwzs&jZ|`!5vjrjsbdJPPZnQgBEPZ6>PD$5+2N;3vYO^96YE#DvVNQ4HP$Bm4dwFsf)Q1>0Hx!uMO za5>=LxP!@!9=v=c#gt%rm|*Vu`TdjAOOX+GDPu4v-^nhu-gvP4%AWzcy$ik(brJ@T z8K@3(+JXh7twiuz$>X(S6QFLKSfRFu{q@=}Hlc)duI4dLe0h4ClFio`*UNwS&3r+e z#7h3Y;nL{}I)%#@(EP^3mf1&=J>NmFz$82ApuWLy1T~2a3}fLeWi?by5bTo?oVhOA zs3UR?Pslu1@Csg(HmGyN!dJN?6i)^&!E|l`Qro^6o)Fa&yY`^A8?&ZHVxUo}1GE*;erg1o@_K>TRIXH6)-@XI^$%A7xm)p2${lz1A zL=nz6Gb>0U{n%7x>xi!;4f-1d3b~$VpA(GE`($ zLpXh2mkmdu!G>`xuz@peu3srO?KAT}j{qlG;-pSD^j1n07N0Lrd<)n`6A|5l8xb?W zITL~KcmaSnpb7OdzO@XnZ4`?XvD1r5Qx|Z%KZaQo$a<(V!gKI&E-jb`U}I6pVl`)HzCP z7hFN)+ggAsmN|JmAW)y82bEPksMBoYw>qz{t4ct1 zmH|IO$6vL^Noz!%dxx<#R(i#vFhD*>mOX@-(3T`kir85!r}P?g?ZQg4)5Z zIE*tpS31|KW@1g0`h4nz79g-4SLVhR0Kwk_@M`bSc?H9-D+UqYXoEcLm^gl%Mad2QRYWq`ST-VvASIv<3 zIiTPKE4LlkT=CY3+|S65UzA%toaPkyi(CD5wiFS2wRWXMrmlDyaRsgzuGjE7KAb;S zHdx0_`X;5bEA5NA#ptoevLAa0n<3Kf+r?-Zdcv^Sh5EpiOq$TP`JYFNB;CzG!h6B4h4`993ftF|$2>z7OCWOu)VWc~s zw?=Y8cpCu*XIQiKK`Xf(dQcpoR;r7uYRDTh(a-Fn=&% z?FRlXte&etyM^qBu(=qY!uU4Z+?QHEXQz%qw)oQ?75h1<*5PzVVWm8n-0LWmEt;)S zf5_5a6umn7vJ0oHaDlcrzQS_oP4LvS+n}x)Hsjv+Dddp%Nkdc3Sk^z|cG50`yqk}F z9B?>Iizo852?g)@@nIGL%!O`$TePbCi&odo@FRM7m=Mhlc(4WSlj*xOm8&90^1Nnm z0vaouU4%cH+5mABvUT*t9>n+-IKs`7&S+GnzLAH^3V&{O4F-IGVdN=8WAg(8WbZIu zDTn-Kc}4@8zbOHy+pO~$kFQfyZa&QEA}k9_#>ctR_A_}gdQq~|_2w&_7w}w}h!4n# zzS2(jrKiF2C#N_j35u}hV9qsf>Xzs$AQs{URu%3XLXttYc#T`NM#^{7d%L!jVg?@7 zg3((dfVI==$l(-5-Wp2ab{cPv&cb6bBGToqg6C<*fU9BGk>H%*7BiJyap7#G^I#DW zdT)R1T!~&swy^X3klz3%UmQdu{S&`bVgXiMs#7>!Zf+x$R7yHI#%=zSg6~qc`$Shu z`B@la4+k3-qyTP8iTjE=W7I|UvZSoMk4?!u6`{3DbEV*)!W^&9Z&n};N|1P?yKv$p z%W;l8`3U^Jv%hOqfm)v6f#89s=+b<#Za6TV&DmJDi^=k)C|w3$F{ z(#svQ!br-rU86?{Yw1T2-yq7@FjtC#G=i!4Udl@LS`eim;amKJpB&_S983BM+T3X8 z#m|sa^XaM_<<5Hh@haox2~xS>1@vK z-;=NnEK2ME7jDLc8%WLpU!Yjy`ACcH9)y&C=+&Frr9cg~0K6n9Q)hw$TRT-Y+q55b zcrygru?9cFgiXE0oL_}r&kGB52N+%=hv@R-eJnDh)4lcKTmwM6D z=5uDkf|4@uZTPl`%qvF-P$#?hN*zR`KZpr}^uE$U_SUi-pq|igNyn?O1wf3-F&)L@ zQ8sbT{Kt1LEMEf$fbtr)G%jH(|2A1c|cIq{6qj57YxP5&Bu%h@todcdd?o!;OVfb4UE(8ie4? zi~4XidUp&oG94im9#U!1KCf5LIsc9~anI6;`^)hg89xz$;`m-wQKeM*^5g|E#J66f zT16tVK((}ggAfgtHpZ}1D1Xv4mFIDNGBa`Ql-GBBBjI1}6$5q0qe^*gce!oe z^O5l@F8$(d?g)@GO=K3YA0a(xB8PFhqQq$J(69>Sp(l~yEiSTnE7-fyzGu_* z_Y_=;K;X*C7f5BfR^mw`v>xRUeuuvd;ufHb?$9}}eR zp77Og+0R4`lAf!h9FYxy7M%XX>sYosT&>wQziEtwrY087XX>N1+%X8$Z1HGZ=V^!98S!9$BT!-!Vx66S7*xlSMrH{0bP0?oSX_hJ#{3f7l_X{yfxxKdltA^aynU+-}?~I2BFr|$s>SV%P(Bm zks}->LaiPh@Dx>G(h6}rX}Q|Xd)im@0ul=kB~F*IuwlI;6X|eNms3_t`Uaimn{IrN zxIi9AYS~T#!yyZz*{F+39A6H3qc%YAD25HE>b-&7hc~7=AyARyZzo)I;I?O!o2~JB z#BrAEj;8?Q=rY=bhT~!PowxEC)y_MH61-^hugu$dqvM6Q7Ub)cHG9HZylkHh$D6zj zCPTK*8>=>xd_zn(K~pODCkmFQ_)m6)iuuA`5+bWg1R-T`C4$#`Q!Xr`G|wRC#@P{q z4?zMpoETYHaqKxxm#YF=xgJhjj3!I2Fg{aB`lkIW$rTLY*Lt>m@87QbvSO>gp>Od1 zNGDs<6tA&jSK4373#Cde_mc%T7ia{?pGc9qfY_uIe|we#+Hvj^lSDzejz2PBW->9S ziH!+E<;9u0sbMJR)?_vAP8NY)$2E9yx)dG3YYF(7mQLI(JtT}tZxde(RaPiHluFZf zoP)3OG$n)^DD*BDe&raIzOe64&zXKzaj5I%S9%=J@xneF?PH;k0ildquuSs{CtWoiv-D_ubt_ z@6(IfAW%44Av4Ci2^>EaI=!+EvSa;jPoV5VEKc?9y~bs!fKfEDh!(yCpFBV%A9(c@ z)+KZW&3&D2JZ*4JyCZEK;Jf}|e)7AH5}kK)>6z9sk#E;F z0k|ls^=l(qflb+E;WwmJ5AR$z0R;NEhLiD+1=0y%E)XI_F}|pcx0_i^0<@qy{S1vG zTi!WU(?+No_SkO#r|YKiE?d_YZjJIlUKNy`a^?c|K(xs!b7Q) zwl8K1N<_K*o1^SvWxM*;PLQ4ns;Jl)h&}yT;QW8e>+sF2?Wgkrdobk{AY3~)WXBeY zH*MRJ63Q(WMh2Z+@bK-C4HL@F88pW$$P)I{x+xIc9< zWqA?E+u&F0^pvuo&%NNGkc;K>LP733I44dVr@_u-?c8QdqyWzLvOWy|R3|H>a&4s^ z2#UNl(lp3C6DF22KbaQQeF4wGS`5F@S-uLCtjioXy#I(7c9#{E5~0do*tm8U-2jtp zy6ol>Eiu|D{mj_((C1-<2Q6vBIj-^>CfTr0P_D&qz3I2`Si*Wp@@g~hNgAvG4>d_| z)u`M#`aViL)#&LJcsBmp_D=F11+ntEr>?fWMLDR)1ao!es+0-^yVm2K{rV9}NIGww z7CC)~egz%HBvg}MA@XPM;Q#05v~i*geA`w8)%8Z(t3_buf%0>Zw?Rqqet zX-*Kg3q8@5Bk4V7>*)-c0I6%s?W!BudrZmcw{@!`ggFbYYuHyM`vYT2=bM1QLQO-$ z>5q}rE{gp2Vc&idTQj5s7K}e_asa~C!J{_mFXKM$*3=VK z6|2TqkXiN>99`tpN^-c);(G;}UcDKcH{^?NNT6jwG@PMV9tq>hh%80K>!_W2C&etQ zdK?PNZjN!x<_f)8d?E}cG$wOiu-ugMXd#*^`8nKm^vNkbADwL?FX{Q1etS$tn-^*E zu+Q93iih@nvhYjyav6^arw#%nZhjOnyyA9v4qE>Sir11iXM>mU zOQZc?C97^N@js^&91+j^E_PQ$>>|eqiSC(}$yY4zuU^`L!CzfZBZ%VH5;Pq_(}?xd z$$z%05Duw93`i%%;J3rrtc&jAdtec?$}kK2TCvVio%+4-#^P^Ser0(~OQMQ$zaVh} z$4Gqby8LxGQzi2*qI7)uUZlh|+t($ag0HJK0JxA+pDbJx?@IZ)*tD!SWt8nz|3ZJ~ zoEhA*9|&kSQa5>G^}9yapVdQ#q1MywRC|VGmNUvtxE(&2-kBim&&2PU67BR}uj6kH ztt_!noiBv;xwKgD-l8rTI4&pcwCTx7tK5W+mQ-zhQT^sbJsJf&)05xdmlIbz@XEZY z%>v6T{tKRJ!Ajb9ommtTb)<15Q}pL*ny@l`JzEYS`*6X-9f_Cd zswpo3{d3OqDKJ*A^dG7n#T70shAx|tVcty+x(ZVLx|~7_6cJkY^YBL-=&`%xCV#E&#EJc9u+~*TDgl$2oki_)%e}<~9Dj>rs0pTGA4=cwI&% z2_8dFEqG*3_bo*>Z7bj z>>&%RI;YL9LlvnF*-E1Tz!{gA7C8-_8DQBF!o)z~2-dl)=R`{;F+Bv;Cr2GNx(?(Z zJA?~OZ|kq7FU%Q&A zd8Lx1p@T?$ql7PK2|nFbx0E%eV`nQ3k-9bwBss=Hi0c6l=kz^#GY@hp$HT5^3_ME~ z*y(7>BS~v#A+3B4sq5qUz9eJ1=1h^SW2Mv$c4+zZ*rqej1T{%OkX=IJLOe7sA8%U$ zvx<^Y1xqp&%k>8f!2EdFa+?*XtAR3WCMO2S?Rn^7t_9%Qiko+9WqkuRx}wPZ!d{n9 zQG@K)O$zJZT!o<+X{In92xP;ErsX|oI_9K+=(F8!DGhzcXxDi>oBou{e79o`s4N3@ z7)2zGpt2!g`w^VGbiu+1DDV@3irC{Vhg4Tq<=XhZOO8P1QMMTfK1o$UTVjCVxN_Bl zU{dOl`_isli^zdTwmR(yY;ra;#mCKD}*H!~+TC}DFkE~z_ zS1zc1mxjFK5{7LZ@5MhA0&c!BUSZ%`gfLgT{QW-F(7o}}t^(d@N#chw(UTKqEneT2 zX7*FlSx%}&p1O}^VSI1JNxFTTrBO&XrN~_}-uLU(LIGD?4yZhUmbW~vQwHRG60@`> z3WT6QFd-KD@Zt7+pTx>6y>U?2$OrO)B7d8=5?i5fPw@0O1G&cR4b<=c`RCK@Il9Y@ zobF!dJx8;^Kkd%9d!~+scJ%u((7aH$v_7C6+SrWkRT|B;uFvpaU-MY{GDIu(A|kVj zK0*NM12u0XAiq62M;?`V&6Z@@8GY}OR_xicU&bSYFlgVJbl=2hvS6cNmSiDNZ=Vki z>??71rS9Z8S53(>bDZoc$OD(&EPMHe6b)1&Pz6T$w%R~Fon+!Q9C2SRi5ia+KlShk z{~esT)j5yfJ4}9w;;aI2K}{dug_h#?4J3qA;mIJa5`GCvg`KNCCGG^FlVzY3nb;|% zOIL*BIYsmu;5Fy%yU0C-j{MW|&=+B=K!johxH9FEBBov-1t@ZW%Ku?z15D=i#!Z`x z>U02biufLE(^+7jKrNXB$SElWVsp*+38@;f$oVYf2W{Djh?mD0%XBT(fVx<3Ni5RP zC{=^6be>|=H{v?dkORaL0!9o3NEVA-hwH3^HgiD6gDwS3ZCA26oRG8(-qX-pN zb65488cU65)+VTdZ0yGF57)mqn$Q`m;C!{o8B@y2>*B&Sntr_1Lr4HO{*9?@!ld0C zT&Gx2DwS3SuY<^868uUEHlHqhEjSkOSa*GTv8Q)jS(17F!DAvo>FDVY>m!+i zpqlr&n;UFwRl|+J(cmb%(^1GiH4eu{b$8xd;B6;;(AbJ2scR-_;BOBLWc@)O73c_f z%2*^if2z6ar@f|R0~!<1Uk0ljOz-o6M`*G9rB3)`=czgbfYy-MHfzaD>Ept*xh%jZ zNZ)MOPtCRn!piwj3U0&esX!TUp$R8mf!VWZl;15*+O;OZcWEeuNywLs>w;=wxwreG zqH#oeU#X|(&SFr&Kh|8q^oVurOy(Gi)Q^)u=`H$TXqN+0-)O)c{l0z>oT4K^LQFS3 zkt)RiEfKBqKfiqr9?Oz&iai44_#m8| zk=v@5{5fFLmflTKR{+d#A^AQqJ_2S0O%5 zCO}~*b%iL1$TF2{^LBv913&ZsroNq5vH?gi9Z^7IVD!RJIbj5dv+RLZwPkPFaHJ79 z7HdaRCHDi}J!5fjD1@K%fJ;PRS;Y(Fsr86inA(!lcHnkTy8Ml;{Bhh>PX`>|2JK+i zKaxN>OJ(}2c=V9w=?Z3wBPB6O>i`oQW-C!B~j7!~sx?7OPmg;r2c~Yq#6oOO4D^p@`p0UTFX{ zUM|RBse3hLcgraZfNtx3OnNHkZYIdvSImszXULQYCJ%FUe~{mDS#{3^UyIKh+9hPwAj)T9u@^^@F`oQ_OuJ%ncpcr zj|ptjO8O4iRWU4A!VcyzTVdSyk}KgLINgg&LPSmXms5#tV;rl?VDscK#ad3f>kGCV z&AbjpRR@54?i6?0&fUZHFPgu8{;-!a3oH}y>~AUHk3FWihy9Km?fS=Mfe%BU*rDzh zgRw~XexryTN;Xe>_v~Os>*Ivm@;GtVk?Y(CnL!gMBzKQ4gK8Iw*{}xBH139g(+qmg z@&NT?Q0UNi3W(i4K&PGJfpD%j@!$`2%ijX=Q>MJ`niPreJ#_OcWtz?b7GpzMsO3~KmQcK#)9`2Iiv4^M!*xL1NLg=|aJECgY(=GIHT z1~nx#nn^|Y0M#h7Gp%akjpX-xro$8?um~~lsor9biLSF!YH$w{K#blsYf7mV&XWb5 zh-U)oI%9A)1<`*8FdJEQnD0XxKXeL+4gfi;B6I7D`FqbxT(XE)lM(u+IU<=wM?bH2 zZ)DE#@ccHgF4fFlDikH-?5c7)Uc-?#@Bjd+9?l2e#{d}7Bj^#^J&zn|0@9;PXC(i* z?=*mu3oMhipGMgCqoFvy8+?>o42=5yg#0i*IE3av8TR_J{f{c4;$6^(+_0-KD)iFd z8(zU2`?dl}VT{p-;2#$YzW}~my`1weOM9HzUGml2Rq{vF)ggk9_;QKs+yA!7zAx4d zFw@W0zsi*ww{g$7e}8Yr|Mj*>C%}F4-3nj+%uKGH1d6OXMF;<-XZH;dZ1H&L?D!!K zRP5md7KvGWWcZI=+2CbLTcP6P*wK<7a>_4z!K_aFn$<6}{d7BaSHb#<_KA-CK+B4I zAiLZIj+_qpLvr~uzy)N3_if$9KL7cOp>RoXr?wG{CFPH+{`i=b|GK9Dg>HCxmQv_w z20-XTcW9~SGzp;XQZ&e&9*DZk>k&*q)=(jRw2gFY=nT0(disU4PepdWx?$n~{szyc_EruQd98uMG`9l7sPVQvQ3tRw380m8y{Tb~x1d=gZZz@{-ZSR6 zF#yppMXx2f{q1LT>P|=)%eXRk;<=~5@Rv)d#((7XKlk+2V@@BdxA}a$FK7=WKd1S9 z$C6)60F@9sRAjrg-qk~H@?YN{lf2pRQftI2VL}{q8~cEp*n_Nd;q|7S)jo0U2i#0S zTJl{R@kpwlHj*X(j@kGC*5S_QNEq*4H-U&#wM=8^yZ|#9FX3j>l2o5)O`GM~$G3vgn?nb?0$AD)F6G}#>+jP*7X;6I zlWX5Up2y>+ie62jVimT>Ehj@4in|Vg)cF0b_U&m;N}B)|9VL9N z1KP=Mt?XV5l;pkadY#K}cPezLaGQMg76rxM9;SBCGt6hIxYm1dijPlkoJ~{{owbW8 zS<7Z-fi9olTbM2}-mr^xG3%{sOzedQMeXG^(9AsLHx^gdiIT`*%mDFDcW<#PQ-80Q zu5&_vhv?4~__v@1_H9zqYmhG4gKi&6swTe_$GQUQ>OuFiR>9%LZ?-CKM7>P#NgKXyXewdGu68{CK*KF3~+cL;AKn&)YV3}!L{E-7Hc>U$z#X=@s z!K+i~V6v!OtuEE~IZ&gZ53@3ss_xoGb_O**zs~3d64fD(*>?tvXwOui_qlhPI2?i; z!H7V)>{l{dq?s>L053)`p``+$2R-TPv&10n0q(be=$feI_jjAscEZy;V*!Vbs*jWN znLEgJw62z2!y5NR{K#ntluMuzXp!{(4`ts0PUZW?Um`1+CE3Sr3E5;F93#m{WR+E9 zWMvnHV`P`aiB5J_Mj4@`P}Y&XMaWE62><(y`hI`E|L^)=*Z;a)UEw(AeV_M!p69;r z&v?=`nc_Q-FU3_fKTFXOG!KkGc$pP86k><`jx}~91KK~6?d-M3bvFS4-nrPoz_6#c`K z@uF)D_Jtb4!h2=rX8hM}8`%v0%P(`9KolWseDz<8Z2_>{f^9w8B=T1_o1y| z1aw{2;$z&w)a-Me@0Nmyls8Wglh|z4WXtQNjlo**tXlM1D+eR+T0jLdte2dr_cb#p zTc9KIQlF>N$g==>ef)k#i_2R)ikc@=X~w>0wubR8&CmwUCH8h@{USTjg~49Na> z(#(yPU%OwUWhD%(E9^4O$L=^D0X|*E&racIm|e50^N&gDlV=@%L2&>w#;Id$`m#Sk z`(1us5Yd+Ps^wm&1Sx(4L#@D`r4LZ(d?EVuGoX34?^PcHgI7kbY|j+67}I3XT<8cN z@>x8$w5l(V6(?m@g`} z7$da$#&g^>s@JEESA4Ib91!y#Umn`t>cS0Gi?%>F(d7LsNO4#qss&k)iH+%kMf=uu2Kx5O0csT5tZkwQN)OTJ+M;># zJDvi=bghx$txXZhCe+<6$A7hJocqVLFGN zK1R4g>)(!+JjvYFe)IgPxvtXF%wvXi;Y{>;tqC*;Ig%s+xNGjy+1cv)T~Aw$4y72y zi@Z$HT~*aj0RGsGBs*8&uy?X_NF{rjOd34|aZjFfD<4@~mziB2k_%uE6?IL2H|2k& z1iRnrsBkm@k;rwbWIC6WX;S#mOo_ulZ%NvHJN{NFx2ZVjQcNYCYZqRQ(KvPU${09Z z4BT8A?zD@|UY4$$QZJF#S57y|&R#FN`aU$TMnrqsDA2l>7s_FWJPK*itIr>{cg4d} zuc%J)qWo-$fj*^CpcmY~Bda<|B2ZFYH>Q)aEtl<|PAfo))R22OOH}+2$FW-d?j8^{ zrockUr-zIJPH9o^=kY{Dt#Xq2|f8bjOX5xYW=i1=yB`%2{$5@9)=W| zM#H?$&Xw6wGfZBNen_MR#oCPFgB9I!#jniGR9VCJMD z@bWI-)u;Y)8|)~&$D&m=70NpWcYG7Lk$QL`h~;<1i+t{Gs<->UnDg*lo5w2RQW2q2 z8*|;QppkdMiJh1ZsU%qG3LtMXgw$%^MT(4>97$;e*>Okg7Md%srvK0D<}g=jZFv6Y zgOc_r@Cp9!I)(w;Kk`JHQTONZIh``WSbf7ZkP;m2q?Qx?H$q&YLfc(-)Ft}+abhEO*U0AC+J zEPUa=pUm&;Y74*fMEZjm#8d2~9hqHg!eo!rp50esg#1$vN+E*Veftj-Agw~6blw1Q zQMx$l#eHbP_NB#}9v!_5)2A33>O9@5U5pXp=gFV!`ClL#JlMCyU%Yu4BPQG+C!ZmC z|8)n7qluT-*^fh%V9-wMg#d=Ez)0+BEg9l9l6&bz4fMF2n&V!lEM_G86@n*{@@+W~ zzLQt^k9ds64aXL7{m*2c_3&uD0OS@1{AxJHtMFWWe}D}pg%rmdUfaw&v^e#*ls2D9}i1jg`RBO(-?eV zCsbM!2&Vdf>|Jk?aa$=*KyGNc+V2wS_N|R)eFpK-0ZgGcic{&!0jZL$)rMHUT+IaG zm3H0ph9H!o_t~b~NEdj^XI(eOIQc+ut)+o!CsO`%LR}^MWpfSvCM~sJq#`22;^T5J zdolOFWRmjhhk=e<1OmIxDqnBtD%+pA8hns-2HFH-4*jJr=1{iVf_gPeKj#tws$nam zA>CPr2`~f$5q0RYN^MDI+5CqbLPC|V7bN#>6MW|2!~xEYWLmYTEFo-Rpfu^!8UGd!yKb3BX84 zeQ%z&---H~lkj;H(D$4j^qwzS7_GYu56-?l^MZqYGbr{i`4f>Kjc_riVR^fb><1>U z1m%^1TSH}^KKCYpy{X%j9zqgrdL;BN50ZCc6E7ryCR1nPe!<$%;Mn~4nflX^csR15 zjwJ51tfGQQzHHo*W0@z1#qWFA-K?D-(`fmp9*`0}pIg*Zefu_uv7SFTdASpKzm^Dw zQ*jT*p)?;!z_ShV9iU)!evmlbmH!G#)N=Laj3-_n=SoK-h|QcO1|@iYj?FysL9W84 zDdEo=>&|+58mfsP+E}GDShD{^ zu*!jf7uPe5Wz~mu?)$?9==sx7)Y0Y;7~BW3Hca)kefQmY;n}vkia*i_fc_Z0W?jVJ zhwMzw{a&eg?6G&jM3zokC?pLZUkB&wW@wc_sZLrU-M2>e)5x0m(OA_W(ryBRrhad>Jn0;?InA*%f z6!QW-V$84C>)S2`+mTuhkxphlDb*VORqPRK-0!{j05a3h6tUZgl|l?5NyVczPIFC; z>HpLD^zy&N?(8)``sMNF_KRD*!xztOvu|B|rEs)070<1g{(VC=oi~KyDVml-Et>OK z0zOq(S1+_t3D5r&!?&b=FqL>zSUbv%|0zYXFq+8o$K+=FBvRZky`DU z-}38vBN~{T1B>Znu=IkCO9{mCiMdVR@dTS0SjCUUJc^q<(Od8{V&NV+Jw%W7MQGC% zFhcwADWvty2a+H5k|kT9Q_)|9c0*WJLqn9H={uU+ z;51kecB-5|{iSuAS~Rv9ftHWyWt#V29#PL(e79PT^y{VPO5cG=;JHtqK2aK28J~rG zeEz;1lrGNQ)5`C-TD@GM1=S1kOGiY-hCE5o^q1=5LXz%o|5}Wcg?|u7GlTrw%$su5 zl-xo4xTP%ar0b&PiFdwGTpR=@CO*~&(t9V`Nk*LyJWJLKXm^0gL&wmIV~5IVWkS;6(lj0;oas2*@8XyimCKZCd-j#>LfwpA@hN|z*-hKUd7htO{#U_Eoq<-(%yegY# zEkNB9Ivj((s{=^Sg;DJ@qWed@R6z9l(z@wr{IM6HCq}Huj#6*KgK%V2xK!oid21Hw zCb{?7i*G>XGz&<&JK;LQmq4Trn-$O%c8BoqeHzR*HFc0jiuNpGEEk3Wt#ObBvpO+5 zkGAZf=%&qk1ya_r_0s_N!nU1&nC`g0KV(p9=Yupep$#czsGVmlsq`KCB~52R?^GAE zg207=!ohYX(5yn7YwGS|>q*%>-l#u3!L(xhh(iMGDx{^SGN0wZMxBTF-IehMPvslT zLsP&Wc7)$jW*48j?)bDi8>mB1-50PBcAvRqU;|TrhM>ysW?@|JdYz9hiZA>oL^|RU z=#bPRyJ}o962y!&NwspGxHL;T$o#y$E^qr0d{RDyG735%eQF?!Ff=E8I#tn#m3WrR zXzKBF8Il&KOPF(wEZ`JT#tMF;?$BZC1*m!Stc{EVIP+~lb3O+)dx!obl;nkk^vrPePmV+FS(u_+Gu#Rcv}^ZkI4$$&h*9 zM|?d!wpaZFe{(gE3RCun`A*+Mlj;kpw(LbO8BXvEn zUdf%qCn`-wGg;K`VMm@xpBfw70GZf5J`{;0I_~H)M~{}o2r=JT&*8}aVFj<#gf*B| zW#vK81G7ANH8Oa}nAvmKj2eIHl9%avCD1%2h2+Z>YU#bdah?W`5B}Ttit8`08 zaC8mYlG0_$X1;Z$P)l!LC1;=F$mK!x#)^UBG{x@KZC5({9?3cn)ZyU}8N=5eFJxD` zEh3m_XZy>FM%#h7Zos}6;0MI$__?Rm;x;s55G8J#iexnU;b@yV4%uYyIZ0_~Ug3O# zPHvc@ydq?NVE7J19|cXJQOGzE*bob65Ui})F0S-5Kn<#(ARvM<8h4Cx4e03yIMB7q_R6RmIn#c zAKEK|uS^UCx4$(8pTb=47yea+hdozKh370fPjoxy3sqq**AD5Pmp!z=hAZHppuO@j zY5c6^N&me(t-n%Qa!z9XKJ4c_K-rltKh0`)4Brzrc|cU~$aC}6!%3CX-)kuBmE;#) zw!a*gVzQASx!kv@Y{Sp?6wh-vL~BTr%yEth6&{`FGmnEUX3jh4Y~bVIx1GY<-VN3F ztCEYVf)l5oc8;3cMWHkN6#i})m?L{bn(saB2#i&e$BQHs>&O2Sw6*9Ietc|P3EGp^ z6Ent$kF7t13iP4;LiMy>={f~Pqgnu-$R?Aj0E7xRnZ?W z_7?_9^QwGO^(G~C(a7CjDNZL*q+o+GwRL}w!U1|&hACrwISnJ4(=*E_1j}VhMPSOS zZr7+~iN0^Tz-r+)&Q1sk=M9Zlj5|U|0ADWm?StG>(brRLmMQQQlEH6Mzi$`&+i~2A z_N#BLTE|W5(TYyxM)pyb+qRePtxRxk1~TlPZ>RCBsKpg zCx;COyMQ#rK{@bx7VS*EP-hwh5+T0||GCbtpCkiTKZy)u_2x|3oi4|r94+xI6k z^2gIfO`bTWfJ;71OoQ9km8z`UPWI=QkdgSmAr3`Jg%I~aDq&K~`ejdp^1AYNz%Qd7K=T3?;amktwP=CA}Ss`!$sG*ZG@E@V?&9y zmwo46r;_}3=)=8fE~$6R@m{oiRo^^)>mJ#yhiRFeMN1GIQJw<+=m}`P&f&ZH3slTe z=2)^cC#p6NRO5)k7*DiqY8cuWm1eGhK9uZD@-#?3ZL?AQESFWj0roI=8zZe!`6ZP7 zriKK;FwT?Z+T3ZI5GNJQo9q{&E~2@-@$}y$!5*5?B;@tDV{d~jJ;pUiimf56^~(_o z+N+HQV^p&og^ypzpIQ_qT0L~38IfSzj^YnjK7$wOPa0iE>v4U4q|s=G5@O=o;%z!b zM8C4c$T@ZS8Z{xLUMkbb&{`2jFg+Z|wdshRGnr6!nqNJ3NtXP?LA>JmW)o z$&A>ZgB?6OX{sb~;W^hf_HD&=<_9PEI0y+}_vOrm>};@i$Sn8y@%9ZXKA))ah0#*xs2!Ahlkio2HdO_t0t-uj} z{AcO?0*X>bZD>D`$2pwWI{(o#Ag;Y0s|3NlB|ZMgBB^vi@F~8Ts7Z8a>#!9Y>E+{- zazvr^Dip#G<*-_)i)vYFwmLfBb)t^d3)QlFzo8S=lsczgI;v&|0gJ9O7!ImMyP{Mw z69c$M&+?Y=Uw1Csj!G@=Fl&C3$Zsx4$Iufl^R?T_rP;0yfG*=~qp3B3bBw*TQMr{X z3_SSH1|K$B-r}*%`2ISyLk+W*=@lyTtq&Tm>n+rs*H8>0=}Y&X&A$#uy9PaGd^&e> zT)^VvQTn`lVUtTHeXuxfO-DOQ6Q$)XC*N&k9nZ|y<6BRT_oz{J-GBKLc5Hdz?&s?J z{dQE;vW@%QJ(?fpuM<90x)hlV%?Ta9Ak$*<TpdT2?JG^E)nRwp^pJItS952ytEyoSU>YE^fOumIY6F~YZ@ z7If-|)*I?dkVajX;J1zWXGi*#D4&Cm)hn6_QLSv(K9%9bHX5SV~$5cOr zUWqbth6b6|(puR5ysyjzwK%p5T4ZX1qG{XvJRPg0S3J>=QKy0d=tU*E1JIg6i$n9h zkYgh}AlrlLmk8!psy&ZK^U->xS}VtC55H&gg_=}*q9%BAhDHlqE6X2lQm7?DsRlt4 zrnN1Uo(nNE#;9|jUsIif&|nM>f@&j!=`3NbshimSE2hf(V~rTff^&e6TB30-+=KgQ z6c*E_BD_ULiMlMA?0H8*K0L-DrafooZbMnP(ND^N+BR=- zvDX>&+DO<>2QHGH8DX!{y#!L!s}Py-Zf%zcev^nRPdIcXlle90sJK}bKgDK*Q`vK( zjy9YlK10A_uj=#(Z>5$59vYo$SVXJ19{zgPx>+0y&+dzizTL`CZBn7D+l?}vTw!Vq zqo(#@!SrFlM__)~ti4#%_e`X>*b4Fq3p}$i zcD%ppXisG)eskNjVkEz&<<*4at7yk1awF9f_*niXv`n%t+NR)8HCAro180kbWOl4! zJ+38wDoN7Cxa3~)q6V1h3#%%)A#0JmHSBwhjW>0lZ$ip%tG-(RAiwFQ$1Zd7>4Z#5 z4Kbvoc5vGs5NJ?x)2aJmp193N7c_Z3mEM{5#oad)d{Uk?P4C=vjDKiSy*N7QFN3<* z9wKwZCSRKP(X06@1z4^9!PB&B4MVB>zp~U){ouTSr{AC2&V%C&AlJgABk|`#t0fc3 zy?h*x)q5yI&*Lm;d>b;t6rl(eSGtgHXaMr*n1{D6oqu%pUUcq z(abJ^Wr4Ln#t$TOu}V-2jHC&tCnweQbMpw$5izNZ3ASKqzqju_Zb@Ajut0XE%V*;< z>})qUhu4G(gRW_|b)mA==BLy0zLM;1>xprQTTtj0ZlT3tj*T60VY{G&HYpgDWEW!L zFFEri-a8&+?s(heo-o1tSEAm_dLgtO2SJUZ4aC^eYxO=sOthtgXCJ+t6N-S6z-5H( zDf<0F0Fi)7W!3uG7FD7jH(2+Y0hOE2VhbuRw9GdZE6_??0455vq7*`tJSxvIBwFIn-idF8Phu5x?3j-Ol^WtU#DS^nr* zXW~fOE>Sb*Q&M5#{>ACInYF6Xw>7ycD>FfyUB$z!;aaOela&J9gVo(Dx$fAFU-@pI zC{ZWs7%UdNxBG`~CT=)Zog}GgS<@MzLLJ&o9?8)1;MtElj@-ff)7kX9O)L(go^u?X z!Aan}vh`j&Li>fjBSeIV#P!Bo@e(>+(p^ zpNVQXjB~x)RNb>DQQLQDU9AWtz3*$N(&^i+OfLT3wK&v>e|}9|Qk&tUZ9x&3&Oa`{ z_z|u<{Xpfh!+*MRH2xTJ?k}7+sctrHH)rHjy;|i#WFp{jzQvWF*tmdw0@>AjjdY3& z#jV61Xwu_m*c+aNZv~zynz6}35mgblSyiEr^N$LJwltSL=OCHM@BH>?I!9-1Dlk4= zPy53&s<(NZ1SZLW(l9OOu*H`L!>r36h_uLjwm&`n_0uWajrv7RZl1C>0kj64vf2V8 z&WEtUrfSsl`t@s+C}+nqW7dL{;m+My6QL(>L)*n6pL+1oeS_%9a7Hx~zBFhn>V}#< z2>X+XVdc5uM_f-+Es*vphX`4!qV|5S*nlBKQQD08%)}sPOHO zp#I6kt@Y4mXbZeS+qGsCP1BRvc2bxEpMWpPwm=3$B zZCs!HSvF<72pfaj{W$ulNzFBy%)Ng@0!0%ck79EUdaj$ib9MK4qtvemC?rT1iO^Q> z&9z3eq3tE=`l6Lg?DQxxvr4nfXb=mjyqE!tcMAht=dt8<|Hn7)02 zr(?OU%^Jt`I}xT~CwekDW(z9!=ZL4H*4ec&l$kNUsGiKt-<1RM;)Bmp#QrsC8xtuS3i-*(k%gxpsULq={}!fN1I7hBWo;@Z@nJJSI(z|#uk=A1 z*CCkQuax;I;xn2y{+ss+C{|~om4-C5%@I>MtsBmRaG;2NyotNvB|^h8q>2C~9EJ%E&oW-B zDsk*Q+Vxw9vn0Vc3Zd^0sEQAIJkyw0*W>m!6T9A43y_)@qLTr)Pz@~~XBqD+I#1xB z6=o6ZaKOMstO-m_dw#MpW6sdAmiujby;3X9pG1ELx1#5*t7RG z!4UX!6`*y?fzGos5jVk*+eb>$1exleFqy3XipMx49w}ZSS!?P(e@hCDH1Bi4vf zO2e~)WDg;QJb~3x(cxEOCZ??;NWxl5IA^q|7-j>=8m~ z?c0v6Sx)vGPpI*glLnh{2r}2(p+-c?t`0!6L0aR8a|}YcUXI?xKm+4I1rQr?KU2At zTw~}M6~cX%1s5`_Gk>{O{k~248DbfN;WHH~uz*Nnb$YY+g<0c-W=M0XdAqXCIp}wF zaHXs(|ABze94C;QJ#abeAlz-eCs9aTd}v{dl(hh+1DMWf+Ri_UJg^^}yj=??1PIS6W(q%PnS`otMmx9N+=;^lzB`ji;BWLP zMjQ6LQvE1Se24|?M49~uq+6e?CXBDG?Dc0;d`XhP!R~^YU4{9^d@ikzF zq+b>h!OK>i5W&AyzF}FovC(pAn{*^cO7G4B|zN{;2L1l~>ai zukZ!4z3~w=1ecvo{)~V=pv;KAs?@gbTdqOeJiy(v;FjsYTr1DhKe6C&zA!HyW(6IT z(gjO``Bm%LzM$eeRTFc@8*Reo^Zl(u%ef(JGZnK~X?+Vg=l8+rZs&jUfrc@1U`~AY zOE_l=;V$s;N2f8Q^3aCQ=&P^-`jY~v`ZH};h{6m+KA}|pgXy{x;@O6hqb(rBY2#^o z)E*o4eif9=;$p)KB~2dai1%n`r#jAhd}jqVBTBW)2iot(sc@SHC`(&-X{#~sW2^HH z@xc(@B+B~qul4r}8S(mnOw#M`52!(P;Ix-ohHFfD+k^3m*$?e%{;N9pqHE8-NPj@K z1i+xm4tR~Ig9zVboQuuNMv?qXSJap26>&D-a7f)T#ek`i9uj%m`)+XyK#zWyV~oWO zPdo3FFmDxlr>_+HvpxyS`b4PLc=;Jljq>jk7SsmUaj@)bQ|rR07uS(i@cN(oNf+>@ z=7C3t+AtG-F-}*D+`y{;Y^3WJ?c}BE-op_ayPVwRrUHuGalBOw$)rO5Ut4 zmhRQMOUd(P&A4CLMn>Z1z8BXDGpx%WI>C@N2pXkE!X%@)KQcxA{v_LS#&l_>$xhI{ zfW0{!hilg4LJIdYM{Gm?Dcp&9we<)M`$mxUOeKOPfu?o@ZR6)x^$BHwM~9>=*D1NG z=$u#FlRAk9zJJN<*D?m)ITkEhuIruAc!#a$y-qGCnd~)FC()*PTN~8OtIbWF8ME(% zZq?D_ZvRqRJo4ZV7oZF^Zin{zawVA68u3ksR>1LL0fKt%waCa~+|!8TwzxsxfJeO3 zyw1|G8XRn({tiJbVYk+&1>=QI!X3D=h6d_O<&eB6mVW5stmsO&CJD6RcNe|AjXn?^ zCrqRook=g>LN9hK@2ng#=V2jPYt*+Og1vxuPxdK+-|_PscU|Ct+g3yCg6wPt+On^J zOF6Lrz!7r*{GQl@wJYrFmIzbd`0iRFX*U2eMc}XAjI7|ud25@H(ITenj9KV($(N1g z;ALtuUJ54r1TC2b^aiY@CUMjWuB9u0$=iZrH_;c2M;$($#DDHSIy#={=)TP>J%Ah@ z0pM=tbLqHA?f`6V2^M1&CfF84_g0l$FY?y8?F$l!9U+(1^WlOp?B)i(L%kNTp_;L`Z=&*uo<34JcVd2g|X+~b+TpHt> z?H5!HVZArO$&9Am`+q^K_y{3R3wF1a>8=+0kPk-|jn@F&7O@nvXnZLM$fe6@qq{8} z=x`TOwx*B{09WholWw19$1tt|`S;Som-o4_4Fm5BTO;YxV-?>6P@~CZSb!BlMXNee zK(luTUe#Fe{1>>|Jv9q1^UghFOyc8)DP`lyFaL{{A%xR|r{zL#aNBdF5(g`2&5nEp_1#D>Sa@n!ebVvYNn z;dWhlZqfMDD344eHLYX4C1JXCUH!Vq+edwacy2@O+BA;cgy8&?gMOI2F*`VIKMAZ;wC;(dMTPrubHZ3|Iby? zwl#KYwsu)yDZPpyrNdQC(`bTsgwN>vJ#*VC_m7rsc^y37?W@kpvI-PArXEd**)LUz z5d7@GH{vy!s_odUI zjlQQO+xXW%HS=40-*MNHOPciyJt3g=7*G$i32I9;ZVSVS!F||D#C6^z(I$LrnPVy- zZ6a+5CR%cALh4QAEP%dwDt|)|ct}s@6eXQdR78o>9?!tJKMq4HQ=rD8jxyvabN2zE zZlGFCzd^~5+dR`HC)blqopJqgaipnU3;@etK1{ zoKW|6&dKBS%KcAf=F{SNFY0Wl3x#<;8AU#P*Dqjp!gFX!PqzN!!#wlkt)+;{wKd(& ziMR_F3(*4J*XPKd8$V4K&AP2J@^v3;^<;294xM^B_z^YaAI__s&W~p&_#4H!S3yH} zquy>#d7K^}E;PcXu!06urb%*+mY4-kp4C#4aF-!f?3=pb`GBTCd4m6p6{6#3T*J0= z>GG^HTQE)j)L!K2-ekkfkW|<_%Z+7}xkR7P*Lc%$;0m0wxknHmyMbM6{zTm9_F(~1 zgT`0!7^C)g4W{b~}+%1O;b-Iu1Uh>9)=l~u|ra#bD_ z7pD|=+_Ufj^Pfc=98&~bB5$Aeax!v^s|uNV@LwbYD?dfXpzIn`_>hAfMIG`Bwi!2c zd%UB<>jftq>3fDTl9mOJl=%=EJV&K{293AOb1n(a)_pd_+^8RrhPiclLzZNMPU53j zV-lwH{3sfr3;+TxDO%Q(g#2FW*xRz(vQJe)Naue;t7v9UiR=5UK#->O`p2u=3UqHs zuV{=Ip($y}RXC-ngk&u1qoO8IB4FAvk20y$t3uaCuh9RFNpFxemR;k`{}~}9x5$XA zzb5E$F9+B~&7g9`v0+?MpRqMRC@wrCV>vkvD(zJIE9L4dX8zidCDF6<;*zU z>zdNh|158Vkff|Tv&b`lI8?s)6M z({W0am^L~0O29x7p;OHl+YGgSIiu+7FM?8=eP5+Jb7UKB1Rpg?i}iaDm-E^ko+TIE z4k@2tTUk-3DhUcaT4WB`80(jH^o>~2I{`T#X1^DzXS)B;d5hq>g_JBVjY8YKQ>Tv- zm}ZTJH*kktg)jtIPX&nBGmQ>g`CaE|m+P%THD9JqEgIe*l9pP&b*VSUWv2)O7g@B8 zS7f9SBPT3}WD4I-{{ygMSP?i3ALI__HZa~)b>)e%1Ky0Z+x|7xdm~IXzXX3AxS%$6 z$T{}fYbgG+zRL{hJpvdWPs*gu852c1EAw-O0`_@{-!SVFzOxIp^rs5zc7aw-Dc@;w zQFR#u?()efCHGYFWx4okDmq?gm)mtg^Yct0t|AJc${{wDa zX>$~uwd5eIf$3fa_5wu??W5Fm9#mY7D7IAb(Yw3#8YmSYjm^~ZTzFK#ap*JvuKsub z3vg{{5V70=TpQe|`9Jp`9Nc(Rqf1)l5wU#3E#m?ILz`#TOGV7h9{BG?u!OyQXDj|9 zh~zfWgQm;ky(#g{F0{G*sth`1boXb{@^GiG1R#7tWdl_HTB5si3o#v}iK;(Pxe`H& z#HSY@FuX$>aTOh*91|Agax&wL0R6+v7DowF*fr?EOV%xiWb(?MbO~A0a6M^JJCqv7 zTOiPFO!jh!OCYmh40DFt;=GvZIz6&(1!6npd7>tlDz|;-d#+87nGRb~qN^OCANTgd z<4JcEgYW$Dd8v^P@2c~wR=qRbk|ak3rJjw9bTDhWuIDS|=;ve&QqnCwU_9et$gL;s z`8G&2AfDus1@?w@-W!>t06)(c-=RMiC>J-W$?2niayJj{(SiiEPgO#7osW>fwJ+Bp z^iLPhQuq&^suv4*s`J}EzNS&SQ|ml&lVevT6Z(IS9=aU@0B9_Rw^k(+tEKap?#-Q< z1A25o-_w`5mf?uGh)+2v^Ie`V3R_IcBc+7<^v;jiu>j`X=5jtGZ-;W)u)uqwRDg7U68VAsZWre!uG0;^T- zWo{DLuVziY?eSjUymGNZ$5%SfPkME2{r>ZTv+?3d3#FTtH|?KJa{q|=Qhf{D-Bq?d z)$aVkV9|^Me$jHN!)Z}p9*~)#DFK5mQ>8Eh47NcXdqQcOx!%~^2M zWNGh0us_~1H;gFqnvTU;^?oyvEK-ingM&7gJVvN_MUEYRqk4X?q z3z$WJslW1*BPQDCwf69BpUgG7YmGmD!{kzxvQoZgTPa#*1SW@^yUMOAQf#KxzVoZs zxTNleG|S7pUJuyalHxgD$J==L2l(E4r|i0}LKPdsRHpXWB4F4DAf9>Fp_Z^8xWhNJ z(xxWpa9OB)uiY*N2PqUG<8L@76d8G>T&~1*sQy_l{15QaJfGz5K#rywc;duh$&h6i zLc^7IBKq+l8!nZL2Nhf$a;6-Ft^KAEGMWdMw1*66Xwy_}_3ovNGb-Oco`n5nkC5a0}AzI@^w2p(j;A#CS{O72*sh5@KINJ^K zO=orJxtOv0xlu8$ap7`Tqv|g<+puw5rhT?4C3}suQ|9B=VDX2!TstC$odx5?S#6Fm0y zYuOsPNE=76Eg#q=4k%S;(t9@C;>gPPRkr>eP4q7g6JO?{+jI$OM$>ohR<>x4V8~m> zzYp8!cJW9RT|d*o_&1tP@X$;vX{FK;+^PiR)t;-hAJL&(P@C#TWS`r7Mq$Bo7(TXQ zE_a$sBS8GBjy{E+iVBS*UGXR8rcS42!kk|jRk{;R@p=1-tT)wIdDLBN?!=X+j-pS$C2wF*+d(@qXWN8Pp;3FGrWZl2@;`-=U25O`n`iK`lP6Hq z7$pjedr#u4x+-v!)Xo8Mncr0}MLEP!K2FHjPKQ81VVjAmwn*LkTUXxrpK|l$s>} z0HRRmS9>e$Rrt32piBdnnx6;M-Wv}TT7_9C%VE8EbRwl_t{B(#33hFJ;Ik5Ja;z{a zE524{+Nk$EE2p$WRAxwQEi$EgDkPF7#~wc&-%nfk`i+9#iBYAGoxr&pYw`Y0@ zxX_e!r`p!c^w`h_UNHlsO-7BrG}l&~Mn!JLK`ofQWSa3lc(IopU^^?rHL^cvo5dGkW=d znnLo%5L_P)Wt@6=4C=dotzihDbd~7E*)g;>2S>=1o|+jE!VQFT(i+JDrj!a_sAqGW zZ=b2|JUMh-uF>3gv8`UEZ}o=s7I4d*qi?3-&#fvFACJyM8)c_H+(S#is?4WF>lO31 zN-^*^xgYC&NaglnU0Ob~O2gIqU86SpZo8Y~Af)S~doILdWFggRkMuX%;m-g5_X=6< zdQ@yZ`Y)5Q>ncIP_vp=?KhzJ|94T>MNjh*DL;q@W_h8|(=Iin ze2=0b0#FL_5l*GFu-!aFejK6wsNMcWd0kttFbVGUA$39d4)B8f2^D}1Q6kKxW47#} z$3%F9UEIbqhv3Z;FbE0+5b+mH?ZiL(-(G}3w$7zqE2u+$WWPyaCOp$Hb?u3NA(u7e zleZS{acNah;2$K!#9tS`XB&kCWo@85%8wMQ=6ZN(e6w^3!?*)S!f<1b6M?WjB2yLs ziDEeDQrY!JIZGVYEVV7o(KeWRZ-~}8(myLByxN-xdcm{7{P_JU#|1Y9k0mhCTC;K^ z*_fd+a>=zPq!N={y)M4hxA_x#@#Kwu7BSORXq!_l0Vlpyz!)4zE&oTpF-uHjFB(1T zdvSaBFXV|Ezf_jQp);%>{FzX9)Ld=pEU6%NbC}fK(Eng)XpRNqt05otxUIj`DU0rO zSI|gO=zLL1XZK}=4`JLp58BVUY2rmzKN!pY177c?B~z0Z)}`NhM~+08w$_W2*^ayI z7@FO}q+ki*>up)29{!tOB7=&%V`<$VJr%I?Y9>YaSf%~yO}hkSe>6~OG`USoq_f~b z#fDyf@K1?+hm1QC{`kkG=e)lM*T0byG&<%v$jPsc=Y0v~#?ECY*Q^Z3!_$q9?dG~d z@OI&}Nm?3mu%>(y=e3RgJ34@L)DpuJ?-dleS}djg`@T6e$hq}g=S+%%OuPtd?)3^( zIWwm!x|6|VCi(VS$-vFkeFrDf2Ffoz`1rv7`*-ip6pn!Z&xGq$4(nU446YoZ^{}?Ui(IjXrUstZz(7RuspPorn9-41|W?jc_(Ph%} z8AD%TyKKAa*~MmH_-aww@cvZCjm7bkFXzve*uS+g>)!Y5L(g@4qn?D>-oxlS7YnVb zx2&lnSsjyo)&r&I3zVqc+lo6)MeV_jX{9Hga<(ek!h~2LZGwl<=&QPS_lI+dIm)r4 zGxLBqM_aHJrG4@%v7_wOuIMz?sy}$t>%79{&Qh_p^gP+|%G@Pq65@?X0UDT;$xEu8J1@N~^u;L}fp}qzbIe-U_26{`%v#0tKiw;$)`7b!W5v z#QSW_PPo=3`>ESWXDCTm+-yC)F%q1dvk<-gB5~c!g3;6~ZL{hNb^Os=z{Y+#x$*v` zMuJJskZ2`^rPULY+n;9VeDXX$WZB=SH(Bl5U~ewDc=B=2*Le5im}eUg2DZOnx@^KB z9(>^SAi4S$E5>#3<}{Vq)um@*BVP@2U9)t=ru;|5ZvN0q6t*wd=QnG9;(J3+VQeav zMA)^QKI0wfz*ucI><@#Cw#7(Tjj_NAki`6BX0`xrvl5Z(#k)H6s*GgvXSFIH>b63}E9 zX%|`*m^5Jpy-Rxj9OFOiqFVZ>Mok%ujz9TI19#LJ!Z)|6Z#SvIwzS$JQf@QAq-|N| z`NgzQDmFjIE6MxR)S5k)LTqMo4d+QLMaJJ&+!*9b?xAmaJ>2%bvnS)>eRj8MoR11$ zUjgR=UY8cvkW`qhv9o5<62nEUyD0joyYgOLN$nBkk@|c?zMbWt#SU}UA7hz*`#D2a z!mpb;_ji{^8fqePpf+9h^qYtf^Bupj@ipG+VvdK9-Qd`zX%}Vcij|UofOKcl?=K1IGV$AJ*Ll=Lo#c!7X5`QH(ZgF1L z#<6NSBJ9KKx$GyWa5oCke7?R8zpgQFPSW>26JaaT>Do!0Fj6o-Qn?HQLr}0^@fVio z{j)`+9`e6tm5#PHqDnrxL&V`Ay2%xF8pt26*QX5&BEOCVv)urTSfm5i)0S4<8y1_+ zfOc(mX3c~Zma06lfBQ{sh*996dm)gJ z5FV}lho%x`N=(Nq_4#>XgJToPgnRM&#=K1zHA~E|kNVGcM+1%Mfz-{VWPD-2PoMA3 zwAy`)5M(q#cP!J>v46%*z8LoIXFP|;Jn-t(8(XTEi`;WNq|N1+-TUsZ3}@avRj#MJ zyWq6p;5y4Aqk0*I;3;4)e3SoI)Q})i<5v)c=w&>6@T92De+Z090@h~ zP)qApcF*67Rv_abq8C7X$jsqD&=TOfb%5!t`MY51TUk6c55S3|8#>gspf$z=tm`sz zkb1ogZPPd@JdF-%ZagYjvcqsh>M?sVG)nAx&dO)aL{43$zk^Bv17>^l@9jzug)rbi z_+EmD2?0>HIB8T|0OYc6D0Da(4;caPE`{qm5I8Quo#uiQ??sUEhG;c)e1`||PNa?Y z@1;v>aL^?PL?;w|R$|><=={UEVR)n8rK{}b^76mPxpiDuraC@d%r~`%u1v9=ho9e} z>C!8IxBykG&h?z`9r^}6?-|WlibX){TQuO_*90Y)6}Z6zxpBL|X6O*~HXJoOxc)?< zKZ-W0{{-Dx+=)LMXVia-!r@dBbSUCwUcOWW%s2Zhx0*o>%$Vf~XbH&-O27`zr;!4u zp!5Nc(ff3`hR0+Hrjcly^vIN6!9Q^r|BU1GiG}sByHLLz9m-PgXrcV9OC_n2(ha`J^o#E z`j0lOUWf=p|4vz#5l@VVvgcDLEhC%3FRC~8{Mm2o&1^Ve`xFC@lC=NXVm()6G2*0Q zYWhTa3+(bL(F1y!(Q6dU$(|o6JA@=W#E<`qxi&Pm>JKJB>0U~TO?03rg9nc_h zF?CfTIkA`YI9_D0_UG9cjMm3DqTf1&Oa2IWpkqjeaTsqkfByV$$O#}j(hpAUeLJ5a zeE$wQ!w`sACcQnH$LMegXN-hi>f=RJoTSeEd3-7S#Bl*H`IlV(wKX%q-`Nm;e!KDe z+WlF$qYmQ1=l=mXUGu6|gA)VdL4k@y<8`|Zm-#EdhF8<>wXXRFpKw~;_Rp?n$-P(k zy7gE=7UA#pNy@`UN4nq8WM{asg8q78THF&5i`T)&+llou2zL-0f}r~2>d})YC}eSo zhhe$;eD%m*v19#yBD%!?!`5}cW4*WUNJS+piAuJFhis38?5ylElP#loB%7kF%#iUQ z*|J9=(GuA!Gb`h<%goCE{-JZ~{NK;#{harlxA#21-|su``?|0Dx_Y<+rXKvWjZsLP z+H%fr@XZe42cgKG*UVzdh#HDMbK#~Bziof_$sws|SkVIs(BfPH!sGgyi1Y}EW_<#F z;0r13oN45s6Tbr7Y7FA|2y9^s_~0Ut+-w510N!cv<(l3`1WA$o0yYbSpxj^%#PR}= z6_sg}N#?aOLDPSQBRZ|mFGF_wfsmsl-7zC0QB+ozD1hb+wX|x=vs4myy_L57J>$+l%Y=cH%sa(jnf6VB%T#8mY5j=}C?xB5 z3?jPn07yF!OFuze(C>m1LSL9HttHfu@7gcH4!l#i_<=$N^NFlv0a{FTVC7@E^+EZK zo&zc|)3o2ohcENh;~hFZ#B|P)UIp0J`q!dm4^sPIUH%NxL0}u8H8)(KO45!MEj9Zpu_iP2(@mlTRqM712fm( z4T%|6mK_v*qy4-YevB7hBv|UB41avOm=7Qzf z%hhgB&6;Mo2u={>cR~(<5)p`E9E+=Q1RIFE&}KkIy9!rxH^}0SC7;iX^ZN|5-`%+Z z4E#PgZ}c}17YSBIOHW9w^*gdWr*zgYI?d_D@tOzsDLgK|kHifB<_;Ci%|y$$r3dcZ5HE&%(G={eRfr4k8p664Jkv_Y$3(wc5+@&7bt`1 zcb|QVsAQDh{CJo(C9LPuX$M7m-ILr+QgilLXbO>%2Z6GlCh9Eb`?qgmB| zyDG`#OBL+L(3o<0`}KUKqSeb@ngcLx=Wa}1{e8bEBj=HD?$p27ARz%`D0%A|bUjp9 zL?D*#KriQtz7I{r7K^lmuEgVbbBH=^vP9VZ9TG0^Yf);x9d1%S>$1n!@2()oHSk9J zfU`0ppz(teE7kD*Mj2>iqx5IMN@NBC$wCEG*#{yqS`>wMz)5CeF4y$1^VQH|cMQr8uXgR{9(#$jXD*Xyd8PHpRaQM3HXk}EuoO^v` zc6!CB0@W4n zein|54(SYV?`bA#gPK$?Qfj7c;{D||05*9dOD&Q|dJ-^g^0x7s$h8Ez_CEuZzc?gw zg4*);JhSl9c>be3@}R{tD&n2tVURYw;l&?Y61$9Drgr|kN?8~Yt@$&Ti6+5OAQtd( zV$L&hQOKQOf34%(@4J-`Z#E~!;$8VJ6@91Vp2CG3Aq-OYgcPQ9Qs_ns!5Jm^sH;8b z*t`eB9xIyyE{y@t?RHQbtA3Yp#pGOTx>Pm{y%fsQdB61SgH|U&F=3xC zF-a@5@W)*A3D&@n+YnLZ^+Syo#mOBOS$wEY&gUu^x*rLlpB;v9Mvs6q(|hYkGU9M{ z7kZzmJdVp@$cINy`TCnMf2L^N00LWu@a-?x%_$AOLC1$}J-yn5s znql)!MIev?9pV0xsqB(}6VrZe$KR(C4SugKFMq#g_V4Q!GA%}AXp;&3Jw}bVNleHd zN+n)>?bigtJJ#u-cPgulXsFx6tCHg6L^yWdo{9)RMFuJ7ZiNpDuRu}*p@ug} z=empmzqA@Ass}LCu@8$<$n9}NS%Fza1j0)=?p;t{^%5sI|@0{+2~0vLX=hRw$TmB zDd%}hQ({w=Sl%T@YmPT3&L@BK|DN)lhbWOAecdiBi5x4ULY$hbR5u&me}x$xQLkIF zhpUT+6Ute$5EW|@_LG|O=~w7S$YNwZBvZ|j*L8z(P8(`4LvoLuXj?WG^{%)uCEj$q1UMWs z>he;i93T6#mykSy?MRQ)lXB7Pa#sBzm)3EHu9)zZ6J;}$gMP~M=1Z-DB^)H5f%4#D zX;XO%s5pe`DQVhnjA&{urmXF2uAdmfoRd_1@^+}@Fz4dQ5qDi&9bG1^-1`iU!;J^A zritWtC4B{-^yu;xuy%If$_>5j1R703{h7p#5A;2p_DFP<^0=T_V=p~2;3f>e`CJ%N>Efe5_2C^XQhI1x>VMWLs!|I#M|BhK-Uq+dJ?W{hlBKMM}J8Nc4w4%d4IsXRu; zSK&}PBiu@u)08E@>zMfDgeOubJ#Xi!a!UPyPr(5UU0yLbrZ%5S!7#^xH<2mNn6c+4 zjpR)sU(-Yc7W8y9^BRD0m?|!9QE1)+{e$DlmsLRdh+Q?=C-7zr)P|MM$lNcrAX|?% zMtaNqSP(8emOF)ZDhU-p5EQNswa&!VoL$Kp_2$bY-ap$@ zS3>5S!YuWRUIZu*D_R*>-*z^8L|x=#J;0sF$P3MY*`EH&Obo8i8BRFgQ|b#%FSY@J zBxUh;)II*^(nOD|jlMzRfZM~Dsi;5f-vZoH7pSj#y~A<E!K z^EqOxv`i+DvYP5Kn$3VNxe2>7Ma0`AQ2C3!0qGQIBNcco=vOQ7zVW5zm?3^X_Lz%4qDTv0MHJ8O}Z+`|xA<@O^ zh7jP3!-SK+GwE|Y0Q501b{zO8k%qq+k%RFF=5}P;`wlutS$WA)psyGt`xMW^7o?16 z?ZK*LlH!vV4(2a9)&Kp-T0VG4jKEE+UCxB~XClRfi^6FFim`lkAeoIA8HG%4N+mM2 zB5{VtJ3xC_P8Xct%jbyk19}@C-_hdw2Vjt*J4N_G6SFe+wGTAyZwh|Js0-w){-!_N zV8w@QjgveQEW>(1u}3@Q7SogoY=*E-#|Rnt63YzDUFcMNh3smF*~;Tgm)~VKnCvof zy4++3u-Lc@%>Hi310B4v>*w~sE>$w5$>arilxtPGEN3(+e1T)Pjv>c|9Qk1*3rC~f zA(~-?Ihi@7zP!82b|4)4FmXL;a}>Tt;%`Ju7lCQ(<;HJ|0i1E~d#B^>zYN-k0`JM% zCjLCTV~{DJkX5qzT{tBm-Q^n8Lvl+Yt{km+3dY!y_qf$Anl0`^dKKNfbn;Ni<$u?; z6x|(Ikrbb_w159f5Ce47wV%DT6@hEWV54?7hCI?djdyqQ0YXU@D6$gjr2cm*Nxcc- zrDgWX|AyVf5rCkEyN%KSv=9TeRxYZdly z>OX0|yn}|@2YG!k3nqS5zS}pqb7eA+QhL7%02GCpqW-#vhlWkf2*}t>c*)JVIZlvksubK@An}qGODKbloxx$Hw=$7q%F=Iw7dEj!ttHoofbAMDYH%HzK!40>L= zU41thl?@Y>zN#A{!$fCJ6n}5T|APN}4ZJ{2jEmtW>?x9Nj5H?AN=nnNALguvI2Ez`8x;t)s4 zS+M6g{~`ylIRS8QTb&1sj8;gwdfqi72nQ?vH`UUM*S;)xp11v&W&3hu!|vtH#{#-P zDxEG8sL1qy2D3Zl(kn}y3H=!}R% zqM6n>DQ6_W)G4*T{?p!HDjiT+E@&F~=hagfVb!F4%g9jrb3n^LIfM6MD~u;%Fpc;z z9sh!K$0F+J8%_Xu*^GSf_f1@eD*!CLKcCboU1W>PW3%fMTMG04xR7)0flZXt3Jd$d z%?L{Ng2i7pcQRiMF+jn)7%?|QaHQzmsB>C}TeB10S7H!FN;LFo1Lo+j9a$cX4Cx0c zI(6v@a5tKP7LXzkJ9s#=ir`_0GZ^5KvB;Mw3d*O&!>#pCI3hy<7Yf2~`=>gBL=UEL z>KdPH2?FV&`I`bSi){=IT3U0qqhdc!QxZ16@zni+|ATt|^6^%{GiFj)TC+Q|wYRk? zA<}SCeNo%Q+a&Zp^_m8f=y+?8)oQc?_~F?LFa!k|$k@hS2P~Btt$hU}!)L^^3}T*& zXM{_3DhO?{aE`XS-0Kkf^8h~$I5zcrf?DYO@2=!D>wD8sG|PK9Wnwy&!}EQxNx;io{xp@ZxDj3V21j9Gf-o}qPk2Zdrpg@Lo1sz;vKdmd68Xg;- ziPKQ5qh>GBKrXDdc;wapmM?~Q;3t=NF*(*R56nn=5ik|$GzF1^Yv2oO1ER*cWiJO@ zvbO-h1wVP*lVdkz0+i3*T+0sV`_gJ^-Itx(xUfbyxPba<;!L&KYQk_GOI{usZxG06vsX%1}Lm<~1uB^ojTN>=T;%d;6|vm#s}pn60yw|$XiAYg1f=Tw%_3W3nPOV=+huR zgYIxw0T-X@R915(d8y%Yz?}mp+sc^GTX^)Bn9;_u0x=HZQs(19k-L;I%PZB|w^wL7 z8I*K0&Gu5@9Yg|F>OF$CE10&Y(8<_?i0^}-eIeq+1;%E;NnXLsM&g1zMr`}8H3Uph z&eTs9DWy9_&K6ziiR!z%Wrs0;6L~uS?Ui`)#9HN*(;#D!jp%ODpW517Y}SQpRm79l z<5K1TP=D2vcv?8YDh7^h;@#*(~j%pSZaPfs~5;_OrgLdYQoSEm;5fk?*<19tf2zQ5rl!@1J*p?GR-Lh z0F=|zTYy|=v$AvT7hb?^Keq^1Z?kmg_a3B$7|Nx0Tra^ycPWc5YdAH)DQE=Bz*t0k zSHQgKG!zORpMiCWoRRGM<#fpx9)?3b;Vki>Eqj#!yEgBj6(7pBME7{n>%#5nrIlud z-l**Q*-&iiV$PEB^o#CG(t|}2wJcKNU_Wq~98ucCWC z0!aq~`!^d;yQ+uWFop$U{MN+m6xM^~n<_By^UIWnCy;TMHg18weAuGB^ z;T6~(*oqQrAg+7a+Ie>;U$MR5e0190Z)4zQWq=bDksoJBnOpbsOmRRNl?KJXlTWD0 zi)UJ@%NsiWOFZ4ly9iSr<5CphO1d*rC>uiiCEw^hw(Zfu0Nf@h`pq=(HuJTG3INkt zF2)6Mtp#`5o1n>^LZJbOeIcTxEqYtV42y_O&r2K1pCE1nwIENoxrO#}wXFNs-v=I6 ztNbXLs)ET&c|=M|#n?}PGJ1}10Y7L$ttR-)EtQKu zd_WpUB-S$37(xd%Il3pf{!*K`KswoLO|ks-l^W{cV2lVx_XqMGH+V60APx?_(tN5J zRlU?Jlz=5~j0_Ydr+qLzb3}vGJ0&b6<@^0BFD4xr%RCr@!*GfOoqQE(Qs%M5ez7|x zjY(;7d)~?#$((?GE|5%W^;_|8CpPxGxeNDQ3Vf1%fX(`>o*naHA9K|!Jka;y+NFO)ZT^ImGW{ti zRZRQfho$@=#Ujz@V8rxU3~wgO|=|hcVUIANb$0&%1 ziKA(DB5!{dQaNk2^pyccK4*QyKe87{%w_3vq|)tPItwXIwIGJa(zg;oPaRL1b&>#n z(;8L)`$fbPP;f=v72F=7QGf>V{TfCpcd3E2%u1FVlec)~F)rAqL7j#ZRi%w5lp0>n z9*D6Fq!hf>pXZ~Aw)jN0CN|NN)--nbS2|r*(ML0O{-5&tYma-e*=}7^=;o|yB=QV+C@7buTuhw1n6|);3PFyb_7g6i8ozovEZLa5K zkFYZ}(Eau+xa1;K1W~5OAYXjhU<8SWfE3UT*5D^KHN97GQn}&5Pc3e&xS7t;vC9i9 z&|_ynwCmdnF2zSdU!elgP)BSa^$qbUrC1l)`wdc59hDEkfx?6peoZct5kK;$}6v8;L9BVG&N0GwiCf!s9(NMavqQSBsN7?vR} zAeZsB+MQi1JXf!C|v4P`o&;JYuvxB0Zc7ami7tK)Vy4OWNJT+YfVCP*)z(yxo%(EEew5;+U_d+9UYef{ zFTJUGN2KtrR(7GRch9EX+W7UN`ScS$jwhaMR}}ip_E>y6q-)4wqdU(w{i~|O&rxgB zue+^_{P6}vwATPeni1Rn(Q}kE1l2bsi;K#l8z9h0yXP1hYDzpg8|#v3^=BSHp7$_p$@dUUmIx#W!E z>|6!eY>6x8yR#iO1evWJUY=gA}9Y0OB0?OcE+=i6f+p0&q)FfV1}#C+@a}_#(Jr>TRnt@^5=gD5HFJV z{c=vN&hIk{SH6$l=WgoY+7m+#`j!eo%6#L-?uK+{WL%F z>t(mM?u!qtt*N=pI(MPiR0=Kf2+2xemPUT~H9++3SE5liqAp9fJ+qM~it`YeWZ@9j zsS+05c?nLd&{uvOrXi{ft;}es8#&uCSE6>=vPhN*4GzCvVtKzi5k-`L=iSKSRna&qApRkT!8@xQF?_>C4tVd8mH_z2+rerem zGi7PtyY#~h=sL5wq<8zB)JlKBHDo)e*mh)5kRjsHbjs6I>%P*)EeRi>N%n8Wi$NGt z0%1tYnQXW_>F|N-oSEFNtL`5J771Fz=;;DuVzZE23^SFLIsfYuNV)L60VFqjjhjOM znK(0qR_+>(KZ^?sfa5KAt91A&rB|fZ~gzYLukBSoZX0ik6z7 zh0wnJ+G6tKDRXRh^r3+~{g-#-Br>5CT3eS`G48t0_{qP+d8@vACAThp7-9$KUDRIA_ihq;E zT+q>rTFJco4=E`j=^-Wl6{R?K#vG4-Y5&MFwkHByn^v?iIp>;T|A}MV*#`7wXXLeP z>bqjk@O^k;RW`dKk;h+`rM0}f&zM31B5RU^Le=?X-f-vef=@8OGcB3J$N(!;8{W1W zY@9iBYxy^AcQdP>A&jLk^PETJ4iPe%BlRAo9f3*F} zOWPgG0y4jBTzuK96n&loJ&CE;-82zw=9KJa0;OB%TUt)H()h0LadQYIhCZ|B6(eyH z@P>HrQy2~u$khNRv=;#V8K6-Scf)`No%G=6ISye`BMA~F$+6+pH9i^99{YPSMIfLi zz28jyPif1zsuw;A#&Jr%n3Cd1<~Q| zh7p|d9w}{?Q)Ujc6`Hat$UQ66_+m0BUmB$$`i;4A$l|5M>C4rf_)r(WFgys9;TelVUm35zZvq-7IR@>L zrhifBzA}}{B}v(R-nR+!=govV%2@yO_WM9Zc&~+sYwv&RR`&`}c5OOU8O$o)Quht< z(<0FKy3LFG(Er;Va>wONjSh^+@Hvj{TD4c#fdiUyf_`++tCpSWiy zCOm%Ih#{6|L)rTz((}|#Kics>^Lh_XV`nbCwLM8Ik$%c7<^qG4IN^bA2VS4<{=<7t zmpc#JB&WkI1wM}0^;f%{06(%g-r>l|fWv%!!h3^&lrVT7p80LPvh#m_7y;s;`8`dK zZ1<;h4-<&sf`WpcfKz5Y06Zy}$u=I~ptf$4%D zC;|Ym`d4?pr2sw3qw%Cfx}o(7+CQn?U{TtROuU*LU&Bu4CJm0@&rklzHl*D`?V3mI zF%Z(e=SElk4j(M5molAz3C&NRnx~Y_yS+AX_Bvz}!ej6hlo$kmNh2>(NxXDN5|M%$ZHQ5a?T8ESC$oMAB2~7ISN*DVT%*Z^S^%C)^Jj6PH^v zt&>W%<6^A1;x&RccUVrv;_q&&=QR(+d25Zk{JDThmBA(N_LPI&?u&3Rkj^Bv4+b>- zyhsx?<&gkST~>G;@ShQDA-EPRU{S1h^3OHR!6M#bSwQqmWcTNNB((&vEJ{DCM& z&@O>GVGbJ3+?*!|Dl1f6F;l`IT@?jR%%6dtxy8T$+o92bl?>B+>kW<*wy2($7w=FC zv^@VYKpZG|!VjWk*S#lPh9@8j$|;b|@wl#7XM#_-BIGACjntHsrdfQB&b{EmB?n6{ z)uJ`I(0=TSd<4s5B1yYf!v_(a%TY+kxIYzxfiM^Oe;0)~LANU}U63BZpD$p2{zgv{ zuX8OV2al&fQTdq z(6A{Guvj`aL917B=z5AAnI#a;n>!Qz8>uDIk0hADL8!xa>#MHKF82~(4g7_6 zR)4iA{xd@Kd!;Ka)N|B?Z?}lhl3op*;PoC4N8oVB#K4~qx*_eIbO`&%n4PaiC5D-r z*Ch0y;*S4mY_ZBm1!Z&^*k$jUh?7NF#U?{!+oRn#=9%pjS{W^&46zloUo`TC!aZh^Q}D|e$$hqZRn>4RN z-2rUaqFHVH+S%H|NW&{qQa(@EG%tJn8WSvAw`*~}^+k8IL{O&gY{jo9W-0=F?v@MI zu8WHg9nVIaJw8=i{fyD1EBC7!^WC+t+BY}8mK&1@pWb>&gpT9OVinz}JTLa^RPZre zAEQ7@C5PSP#PiWNx36=1UJ`a(FaB_P_M;NcRD(f3E&SV>D~r z%LvAT$ft{D%1?aHx^dKN=lF}*br0dC*)P5iiGG^2SUMs-<{NDgxZymQpwHyg6kiaT zI3IgnnOM$CUX0uKGxXCUhnDDj(&?SnCPmz&zn zn?4YCbR{kJ-2H0O{ATOUg!`{neCOFl)xx!nv*E<(z!NAY&O}RwZS7~T<1adX*0_uE zBjze$?tiY%eyNK?m#Milq_S&ZYhkQS&fi~{Wr9o3uflFzk=pcQR-Q>s`~enRgG+tm z!Z_~79kD9mdZo6kHFf(z(a6!7Q@nM(%Y&bbdlta}z1=8I&o*c$R=I??RjB+7f32}v zY|Yxaf8oaf6Ct{i=!b(Yxb*hkj0N8uLOpiz>N<*DE7HB&pYSIa=~5E!FIw!6inZ_i zSL=#Y1j8oEmjX7X>GvD*DOA=BJ};X0>JDg{S2t*#EX$ZXqLbD!%QLmCZCd;NLgAgo zRf7jj2Z~tgXUdM4F840`f3|9Iu5T2q&wu&LvxR!Q`gOs^{bN&uvZcS4iWDE`d{5a8 zKW;d};gH=-y0s_|bHK`S?D9VE??*^&A9^0c;r%)ILXvdW66SASJDW5W-)Tz&sMT{Q zsi(+cp?kP+GmyWF0NYnOAFBPZX0DaGV$-HM_e{#Q)^}zh%K9_{nW?u*E*Hs^92yfl zB^YPbmNQq ziykSh_s`+9m89v8so_aNr`^EwcT9SkiL^9HomkZSW<$ZZ_2}DjJ_$^FlgFV?9{+h?tcJ#ruX8hQ@NMuuHTH#7xkQb?M79RhwH9u zADiiMIOd{v@-Q;mUg{9tV$nsYQ&bY^^(^tj3^z#dvIJ)@s4S8Hc}vc)k#;1tConDT znUJp%30=T7L~-^xQczP+e0x*p*zQM!{>s-EM2T0Aob?_7IJ&>4QyiunFQRtOB3&-W zi{e3(4-1VOIVNpIzToE?0ro^9UHK!g#RJz8zN|Sk5dImuRqH^s`X!dc<-yMS6~9IR zSJ}HJrTuWwQd_9zLa2V}@YTvm#^aCvj&ku%(BY19pNrnLl&%hjpSc^)zwU+w?{<;{ z_=G;!ASU@R)PL;Hk0q6ZyrGWq_lCLLQYSe?2+LMhk@10e^%Opb$}MEp|GY4VSn#SI zC=1eG(Ar%Z{S5gI6UvDXfvT$R9}uuGc`f_&2U@IFj6dDVgCt(RS9&mz83Uu#e>;4? zU`0Y>3W}n)E|Sk=_Z|>RgGY={gjQ#)Ei_2HH3Va|-@GpJ9TSWd%RSpbFWv)$LRjIvpuf_WcxLgI$ro!Te7jHm z2_rixc!pI+LR?bW=0ULTGr=W1JOXQuYVs0+gp1|DJ3qenms|?E-$@SgJ>>9~qjmWu za98A{hcq#g+U{%$UsJ31qKy4#{~GG=O0X^jS%WX{1}RW0!3HPZG$#p7YVTRB$B`0- zLlh)&f2{D&(e@JegO8FVXtdc)AM(rLQJv;~znIx!;`ZO)htGEW21(QL`*(!?T!VBs zBw!YgC?D3}eHz_qc-rvQi3B`&|Dz|FsV-Mf;uFLxCmPl4=6-vhXA7Afrrnx%Z*IfM z;PZa`@p;yGQ5nRg++DK2H~P+7y<>#&rgfSN*!dN&F@pFLn5lc@rB9!ptS@VSwhzvX zgM{JrbVH|+(Fx9iBcqA>G$UL_e@-Viyy8W|y^p_v{02+B)|s;s=?~7{y{~*o1tlp- zX9`(XT0`LTKX=SNJdq=C0XVPVM0WOh_5olDvP04l4!GA9P?t@CF1ySHu%)Iv%lb$c zlF)wM>MgQ-pM4wuKVzdK<$;VMRMmlT=haw=q-165K?HZK+Iv4a8Clp&3(D{f2ZXf| z(D|j1t5=5qF5kSFb`pT^(I#x4o*l4%c);0#O(P?8u!|M96cW=8rdswv;Q`UAbE7OX%T9^w2; ze7>ClJBpcs%03MN=B}oAVMc(*BA`R-3RuU#6Oo%kHcg6J5;WYU-EY&aoh*C&5DO@I zJi>;a7g?R|QUPCE253|y&B3`r-$9CHd)l~5SXkJ&3X*ddT|Ly+&q1yy(A8pW2Np1s(9o=rtu>3@+TNTHLo9DugxP^F6T+eQswMAwJ4xO| zV;n0qH}X;Pv01JgVW4c+z_xBw=27dmy|r2owJ*hw!Bw+RR|th#LTr19%KAKF}^GJA_8Vy2k8Rz|Aj$Ae9Tlh0={!}r5mM{!uTlw$wARn0h%kB9L5_Kpk5WX zuL!E2ZAIoP4*lSx%~Z9y5J)7#&)u1?E{21WkE@dO5Ev|vL33pkP%_1B!DJON0aVm{ zh8mkFi#9KZJ;b2nkF%ut4D2oulu1Vwz!L7Y=3Nv!?imE(I?on?n-bUZMc3EF9@}|C zo!yxhDqa5m{$XHcQwvR0cALjr{B-M7u|h2q_#U z#pu}U;Ev;alit{F6hCKA{O5@!ULAukL4@Y_=}1*6nS7K7y^~RZX2k`_+8|CTnF6i* z_&jtAP5co_0=uoR9l^=Q7<@S6*;UG6lGf_7mZvG$>PD9c6w*~sr;IJAv&Z*^rU5X(}a#F(*<(6*PuhZ!M()NGz~>k0lzZDKSqJUBti;c1zShQ^bNpq!f=nFIE?QJE(?f4CwIvO$%!^F-)nNyn{F zy-(V(-IzYb-JaChx~d=TfK<;EHS^}E(_MRl>D_#ae{d&#+~MJ zvoGxiQIAN@3M{5{r6ZBdvlHK0i-8GN z7B{jK`dPY04q<6{rV7i{(-bc#Y`TNW`FH{}w}v7Oh6JAL!x$hcHa_}X-jR!H&0cNU zY9l|01-?k`TK@HDs*bB_?6!R0JASZQ6FpESRxN4Me6LD;q-1j80nKeIx(v@ei44?4 zc4Rgg8JYhvUXPZ{E!VB(uE&AFn$h{oaG?tEbA0jA7E|nk25;+|-yWaESV?Cc{Lm|y zbEPwM1-3yna0Gc#xYzJV#qaL*oG+hFedV}bSPP`L+4gJvIE`i?s9m+6XqpY6VtW9v z%dNvdDRkByg3XuK2cFM|tZ(R7`6X8!+TIx4j^zrsXkTrBB^opMbzSfRb&usJx&*EE zKw>uJ$Fndx_lLgGmUNE0np|iP8T5NcRX-_7!8Og z8*mT~NtoY1B=tZ~zX>~j72>u>${g?QBlh8?$C9_wL)ENsnhfpe?vR- z=IfH5u=H!r`8ysJRIQ`JQ~F)nK7%3J|bTBv2qfHXLd! zAI+X)p2~qetskWo&Cn5gE!)00Rz3R~zjeo$Bd{A>8dLdRcX(ZmW(^v&YbJjM7ulf^ z8no3%lg$8H!~0D>-#YJ1kr((s794IXDPPJ5>4U+N!`hPav$8hCD8-dRc(< zm9pTzn7{99`!LYIhQvjoI(VL!6+D}MEU9~TP0!oACk9qwa&l2g^RDZ@bnbbbskcJT zilOXY|9H6ePW8%)Yg#gIiOPYAN171tz1ZwO?cH&h)ILosbn)-d(djT;ctKUN>00Nk zYEy^xp{m%BfYq5ySNJexpY@{;?ygio-pxXqpf!XQ&A7F(N~KS$nN3|XJ6JX76R$It zJ{+INX(XMlB_9m&${dDx5aTJYBAt#JD~E3T#o#S5#6*{ z2m zZdfdbp{~F1&PGp)mgw+%I9hEc@uJba)3Cd(Ta%^x2eK|bxJ?J+MS5dzyfC^|Pufdu zbXy}yE-GpBws7^}T&KZl;yk>{(d02zO<3~i^2;5gTOciPhhbTNM{sh|BOArrV z+3xb@>A!+>aXMiHFLiOq;cjKN;6L4wukZjxd<;+{#s>(H1>l#amQ|iQ1Sc(sCL;GD6HLsZ*&{9l* z)s-wU2=y|>&P2EZN%s&lK{Q6vdHLc?te`x1+ zVm>n*k{G?VNP7f z4<>64{psoU8}GjnqHTmMF+Dl>3AfufSGPN+Y)xcul3nkz!03vmt0dYsbzQ*%SN&8rkiwq2b1b{8)0fUY$UNp>GJ0Qm zwrWK`x~!ArGk-(pR4Za?dH{j!#dn(-S+!df} zr_ePewDfee1`vBMZP94)ecoP#7LKWJSbrAkl@DCaMlCDwth;s&rYVF>Z=`wLF#|av zGitkLwSjV`P4JqsUNQM%jNvlZkECO6w3IM^S5PEtekI}HDO!aV%lGon>ut&X&e~4B zA`<$_w*k1#pFtd9f_U|VrXfduH|-SyETjiV3|U|C?xbR=1jQrzRc_Ba=LX&>6AL>M zEkHrHpMzq~u3c16C0>ZW%zliAogNphaj`ykI$9Is`{2-7w-z@xnN{;IT;Ebs$S`SA zfySIry0t80dnQSkfz&w;{b!cn0>Hc^5uMb2i0K%T66>)fDSWUxP>xcXvnj*mG_1Zj zkwkAw7dxk&qfkA8B$;!dmSYyVKL@w;k_@xX{>eFtlnz(?fv<&#VB|>tHcRt<(2k$`wO0#48Tm%mI@FKPUs68y5^~X3=3X0& zq^tm?zW?J_ke?zw583fmd55#RBlu5As}3^o1s^)nyHEniSHU~;cUGwf129?6W?sGf zR!jgU)I`eXw6n7E-E+ySi@pMD$UL9{QDXIPihtW!+q|EMHh>Iim&bwOa zcL3l}qnzia?eQ)vM~m${`Zv%*SOnkjl+~+mHv)u>3OH;7!Pa*L$RW7|lrL8s!qMhA zCPebrLJ+45g~xe!jOy&ZX7@Gtzt=>_b{R+Km`>`@?kBiRFJ4W3*mUkUT(&pJ|GSE= zd={$c?dDH^_+E#kzk#B9_V1gAfE+>O-~JvcfKcil+_(j=s;hDq`!W}9f5(Z334ddJ zgnls0$A3?)1Z%U`7R>Cd*rT9oHGp%XVvnJBVZ(psKGX-`zmVT08Thx4b{oQH{c@-! zfZ`|4{U7hMclkVF3biEQ0+FfHrKH1HtuZge>uEb1fAbh1zoUMd}hnD*&a@ zMcNEJJQhaf>mdKKkOeC{HY71oOuVEIv<9cIYFT$l_?_i;L)9DZ%6d>)QtJ@$Y?5y!R&(Z- zFh7qcEczOTa(H=SE(+P;GaW4#{yci&oZm-Ca1qy^Z}b3ns7yt4`3axhK)+8szzpHQ zdXNJK5DP-szqnA#sP^pgfywst5Zt3Ipq3*UM1a;OP`Y@>u|MOP8DzyH4>KaU*XN;o zJsdjF^aL@)XhufHF(AWLjGKeEXIQai`$4bsrqPf9CR-$`pTbPNu`Opx4u0?u*)BKE z?B3@@V*u|PXZA;}i{Ts7iB{s|G#L+yMG+(hFnttZqlU4#BbCN~x3*bgMX$%+$ z_rlq=Q4TS=`W088$;bql+WrP#bX%OqK2xd_XL%2U{1gf>2OjrXaN#UVIEcM);R3{j ziBHEI5k(7%7rEDqWb8+4=>at17Hi+Ih|GGJkL2Zmsi_s3)ZM&a51Ns+knQb&EV2Ha z`mS^R!W7mZv!enzBg^_cG)_Ia?0Xo|!W)4gCT>9elj2SxB|pJS>{+VVgpd6w0rpwP zxB(tgmk?s3Do)%-pT0F7MEf_)K$xP8d^2Pdog;vGa2_~vLb1?XCnwVtlF*FK5S?c| z&m<37!a(#3!xD}HVDhQgBChqhJ%S8E&^vOTgTg>>zuebvi(rNLW?U9YX^2jgfS2wE zf*=}`sXH!}etv|Dyu@gLw^3g!oI*qlqkB5VKvOCd(X1qh0OF>ASl3W7Ol=!jh*HE_ zwPbcC0i5?(M64jm0Tuy*6&GpbrCW}rqZYGW;~xYy!(YK+i{nx`i}!&3L?TNAV*)R^4J;$VJW4$&|G1yPw9qM z$-)|N(LAH5&vzrE8(Na~H~!Cg7=MnmC8@m&$U31D&542=R#Q9$2(qFX)yu~n&wne5 zND0=dRTf(n7)UZrh(FlTOVZG&v7@R^)Dj&(nmcYb}|^9b@*;hv%v!=IGyx zG#wM*6p+S+R7X*(P3A#4et#CYK41k-QoR+23-Y8T?psI*uX5k0T)CZ!uX>ci0W z`^w)t3iFG^#UCj9wj`;&7bpHjE`a1TDT*&TGgRNZ?VHNX=y2x&hr*ken-JA64NVZS z6Og}!gv|cyMp>xn?8xLeK|2AwThP?d$j^`K@Bj?9{?6(>KpK@&Q}ZCC*Rpa9NQdkQ zb-hpuQ*~8;L7-qf6W2jvf8_YN8x!V%Z;&+{yoSNw?^<#eA&4yol*(UVs_~(nH9m_2Oyf$WuPc@avbgvY8!;x*@#QGjJZGEc!GC z?Qc}(8*K_)b%2SEApvi51MtRJCUapq`lk<@Zl=Apf;vUR!b_KCT2U7`4EXsfp>4|q znh?fs6Qdp3L~|H8f$fxe>)3IEep(1vzE0M zNs^dVBYoz#?MqdZki=838pQWsL%7$AzD)W*h9FN}3iL(d&W(7f7R$u4kY3}tQDPT7~ZkPtKSU+rvBT|L?P zT{HViiT>+*tsKJH3OK8h%!kkRA3Vyv-4UhHlIdy_d`hrMsMxwk4Vnj;K_H(uGO;`; z@s~TG%8f!Ij#E-CllfF9-$S-CaTrHswp4#XK1U<;_NdO=pZyNaF=OpHy}+^@fH@p@ zSFRfUW?8;efilVquH)CIc>`4mv$A_zc77?bD}%bmApkN6{1S#`#2S*j!605e8A$%= zcZj=}$GlRaJ13ETh749WvlY_$^=Yo%eCJjoJ#zH4Pz#4|uA$$L6L+m@GY!ADQXYMH z>9grxRLE_@lJqVuQ^nN z##1yTsjuQL-Wl;}h!boMl72r3^B7lI7Sa3M0TS1?3{}QV{fg3~)I3a`2MMs5EX6Aj z#pj5MEulU_6wk);jbQI+_HH=a8CHM88V@fTPRB`Ug47lQEz1DUqK#ZNa|8p6T z%9TOV_PJ3AHW>0pvIsl)s2~lJjMCMvvf_^Na7UA*?V~s6b}SRvTNZn(#47?}c3i9o zBHsCTy^jMQC~aS$WDb&dR|-FqHGn5plHd8~RQjFN*1@nYc>Vqrq}DC5SL<%J!Lklv z`hs{3{+S$|HljQew@yatu$ z_TELw`Q0xkjDhd1%_vjlhIHq_v(NndImBzJZ(K$FRgVXXwhKI>OALSC?rVM*gMUmQ z&_ycVF6;d*&X<)18+eQX%>VO634xGcp7F8l?CwCFfV{03_o0Pz5T51kFp?2^B>${= zZCx4te+DuT{#>80=jbj%;ynug=zPfwXCXa0q7Q^c$NtY!g!gBX`cZcTh z*Vu>eLHP3w=F+w7XZc zY@qKQ2QopawFl_ zWYzp6{2;|mwN~n=PwW^$X53LMzf-x4msiC9(RCg0SnprBBpD?m$%xmEq#}EdvMDQj zl#-e8%HEPu5i;U6LXwfPXOu!@W|NVV0%><0|9ZeF5^D^!eLt&k6&*W_rO0N z3Pp4q49x}Q0|omL2C5ecn&J-5(h|YXJulc2!@TjqyzM#SzdnTbIili^dxX zC#R8*aV_%`JR5acY0AaCd_10u=C&d1vl@guL;FZ10xD(`lEBgLyWDHMW z`^B)-S=b-iraaU=1N!L=;c9^#5vj+!$HcWM6X~MWI^!P}0zMk=}m(Rf&TJpU+ zSVtTXPt6$(Yu-X=F-b&HfJ32%Y)yaN6o@fZp(DyoQ1#(erfMok)h%?qcI6S~#Hs^1 zhpxiq0!bIM?p$KqiI$OszDq^mn#Pcz|6WAEO*!-!kUI2muC~!t-&l>P!yCU%qo>#q zmN?{dTY6_4DfqZGq^6W>SbIuq`GdtcLefeTZ*&_ZB4 zKVU?`W%KN7*0TR4Q#Iw{Rf;n#%9v1{yIgB`S0lsRo0MbJSDm8u9f#9;92bK00<|>V z=3axy__pkew%?9MbL}3|%3qMTvx-(>8ipG5u=HKO+#PJp`od^L5f`&u3CH;;8;EbO z1)k(M^KNIQghEulV`HVs?gR|bz&)_+1)>KDPm7ADO0w`QeV`vWTE_42i)r@}K7QdZ zF2LTF0w7cVFox35+52*4AvN!$eOgCu3Sc5F5ARk42?OaO`16v(Xf4BW^{0fE@lR8= z?H^LP)RKI>HC>aq;Fx5Re0%vwirdu5H|oix!(%h=K7W*t9C|#}R~DA69J%uhUo|uI zt4q1ixFRWglv|Mos*8N2Rn*>0B&wZF^QYWyV*$Ty429SS@cnI9>aO z>_vaA^c(f(%^tL}_uO4G$Lld?Q`!B?W@|2zj)=xQ&+0lG4pkbF2gVTma28?I^~aXn zsKUl%MU5H~hI(>E73)&{YUkj{^cuj`WEPC zR!)=8cOpvK`H& ze6e6rVx_-sRXlNJVoUdIQKsXyiO#auOEb+(_g>eZU1(oR3y7QQO5!R?u&d0d<#d^q z&?>v<_I9>Qu(@rPx>wOYJoEB<*REcc)Xtb2MysdYzi* zm%*mqSS1i1Z}UC0=c4q2DV_LMSo;zNo5Z$n+ zATGh4_UjZDcwIFcqxI6zy=dZ7{aedT!gw};_?HGcl)M>deQtiJ1G!|@i5q7ng7d~hi=CYZQa%mUw3!?;CClZbCcuA+z#plrJ^My} zg~zq{(QspAhwfChWe-yF@S@mmzM@>^b#0FA$~6BvyKP)4zgdQB$;8G5?!sW=>wD*M zb{L#3nA<_+8|*M3Tx3Ufl))Qd0gC9pC-;|=zDWQRrnVteWG7qQ=_XKD?e`2)njs9* zH;hLnU)PhoX}h^P|242tm*1`?B`9)u6;oo|8y>v?)f>0lmtynJ#Yccas>VsAcUe6h z;xu=jb1?ZlMDKC!Y3h=37MjxNx%!|ttDQgk_o&atyOolhLigS^gcguT<`SDKcCL3V zsM~A?GrL;kKF_f$(dZCXBu)Jip;xk6br^Fw=tL;F%e|-X4--TMe*MraeIs42KkOJ4 zZ?xT%h`wrfuA?01?V2;R9xFxl&JKy&@mKe=E=1M`3$QUj%_wQ$U}k0>h|_JN2Y2FR zG_DKUC#02TQR@6}Q3KIDGf`+ls}9TB9-$E&EMKLHbK)iv*N%w*vbq|3e@h7)L&s9^ z{TLqK44?TD#cw0&l??v8lfeGyT7#bqbnV`AADG6`bqbr@N?1_N#rK;NdH|tfqko}d zdx6V)G=t@Ojz4_-GV^=qzNU~I;GMQlof6)s#QyD*z+O{>55IU8La^^G8lH#!>GFlV zZ21}-Rnli1PG6~+$XdUh`*x%1LSQ1sR8>`J zrU))EG{Mk&oy?nA?hJ0tSCy{*eduN0cp8YCOh53Y;(UCHF8ao@GYAxeWCo8^Ih;IEbZb75O2!q^e8VCeRa=t3lZ>06xZY$inu+%qdX z_RzC6hDh``P+Y8{2p+KkqjO~sRQD8n4&Mr$`sq12Q=Ono<)w4~2c;TD)iVc);Dp~j z+$X1dO(B8D8ERJ8Z#AZhR^V=B#n|HP=ZF69&sW$Z*FLd7D}@U1c(+Jr{RRO9uxzs7 zeb~NylW_pO&2ZrVpZNLJuLYt1{~QUr*eK%5De%y_+K!(1ZA~7GM?$9?L#X|+iG_6C zL~M~U<1U1d0z21G1L&<2Tw*^5?(cE@XQ6ENYfl~T2EgL=cx53HTEXx+$3Y~NniNkc zp(L$*-sd-GSq!BPFPJv;-FW}H(<}oK30#BqcjjfAOy7;QrP7c>ErxNm4=(?|Zlfmf zxBMEO3GQd<4Dn#9TMnUlvG1NN))h=uHC_5TOa{d5tunD#b{G4;9vpQw~8$6BWizN;6n1#1a+dw?`KMJ2kjTqO3U5w8}S?l zpbi@Y+~WmAZsSW0Xr?ep`W@}4zq%FJAa)o-eqKKuij#jZ?wf}JN@UL{;8)W2sljQ%^tV}2o2r#K(jx}d;uvNrO3JRTd+P}zWN6p9dlKQ}^x@-rlD zMnJPMw9@B@Jg}(i^YR3ipvTG+=p0lB`K1)dda1nDFUwZK;{6#XhQsI~ISD#|E{@{a zCES&$_*o+I4@>2_iETlJW>#&KMbpV=J*O?grw;9m)9gO5vA-e(Sa*4 zvb+t&AF36aOk?oc_bhh)#QD?zEG|M;i8+BL^Ekq$Ry;Lf3Jc`qc35bF9b}YR3Tt4K!u3@NR%L6U5;rzrV#Q9>K_2#o9jzj!tMjNvcp|8e|H(a=(EE zopKeN;wEyd;|dlN-H=}{0s!$A5Vu0POd6zEBzzh`_cKZ?eBaP{Qo%Oq`9f*js-_xkE^J#mA=vllE5i zvwLg=hEibv+5SIefZcu(^V-6i53ZMJdTe=byn0t}JH$4gu?`+Ifg z9Z(~beZGTXKX)<3H#Q;)N8mRE*wZr|{#B2=@94?>^MDw@H>_&JuG-7t@qPH*_~rK* zwnl1!(o^Fr_qPz@K|IQtoxezm_OtZHeg&*I<8drH6Pc(Y zygwc-SqybY+$7%MuA(?E-(TmbH|vGsr8k9jq-Y$~XXXzsLpD#m`h%@`L9d!*LzZfK z$*sbNq`#lJ*cS9~dRFHdy5HZa3w)XBFXAteoaWp4fUGVD?xfs4Me;v*wNzpqVH2)dO7P8m@7~eylHB9^GUUrxmpLYYK!9OE~xRAiUpa#^_ zr%)Im+ZZRDg6zMAwhS#*v#&43n@m$5uzz&}c(Rah(*`FtoZ#mZ|9`KG5y91cJU=t- zFVXC`$kiXvILm;@1Pk;72}m;izw`s}o3Ul;AgV50IL1;ez|6 z^vGJx4n;1AaNnnkAgTR;FAxlaKgTse^Y#o+Y)tWy)Phemm~Xxo8+L$VDp1#b#qoU- z^qY-Et_o8k>Hj73=OB2)Rh8HTGA}F=&K?psdBqYL!qw)h`*U~va?HL5e}n=DZ56QZ zrtlqpPmG?V!9X=c2=qFSPMo5_00$@%>a>6i$VZEl+8dL=rOqW=gYevbV=C;$+pw#N z<8}6DiHOk48XE(LbSTtV)J%8fq<|bOCy2i0@S5yTyB?sFObk~ZhCo7A4yYW*f;i06 zGvSA$)P4P2^z;%fFBGT9V>m49TJqeRwRRanqhZv4n{WHZcgA1d;^$k3fYrFq?31-W zJVf}&-3790YGf!NcS$Yecon)%G68oz9R7}`la`i_d5091sAX!mZDBNA;U!loLlK1% zsP@{rv8P8t19}uM9OD4;1uD@WOa1o(!6>Xjd;uSRW&>Ec6G5Sh!F1ya%~iytSvPbdGc9L5JWun?r82UC?5sQ*IN|9@v5gwE7#+^oL;`dD-@f4G;k zj1Uop*RA3;6Hop3k%#>;`Dxtz;8r}bmx}kje=##ygQ`i@MG=6-D%{h?aYqmc}m&hMEA&jhJVPQq902nXabrkmx16zvgdv3fJM1Y~)nil8n`ZIupUoaYj zYN}+2QxyJ6DPUhi0(hv{%Tj$95PimB|;e#h|<(r&#wwz3x z61={?QkQpLnP$D7rTe6y-(9DCZHQnUxEf4gMF%ep?u&5{lKMY>907eI5hWl-Any^7|A?^?`T#(Evzrv8m2ODq|tQRh=F#-(FaBgTJA#9uP^oA}M`ycZ^&juL8A`qAW z&Sz>q9^9HN%K+NykqA!>^7*U%;xgtAeR z2fQ@Bz_@${+C!;dEDifH!FXu77%l8_uW4(EKnyfi!h!xR3&k1U_u{KK6q=B8|0Mpw zNE~>MM90FyBY&(?O)W%+gm4E0ir>1f+fqPFM_1s9+)nET+v4vYlA*Yp))u#+oH@S* ztgB(@niL8yXq{z2A2Zn0ytj02lBjE5aQ4-K95>^U<22#G6qE-~e`F-mAcFpKVAbi@ z^4!5xyh?vkYdF!}6!T#EF$aMF_rTY7 zC?E|X{#obykM&a#h(!k#0Rz{rU27?}H`juuhe$=}1~BiiFhHN9j6~`#;o=J8Z=pGp zX-5|3&Y7^U51KWql9h3*$k%>U(~bani>EPLLlfBg;_e$0EIHIK^1;iM0mjjnom@%< zvyrGBBw{sa+=lQa8CLjP(0YcERem0pcyJ6x{Y&F=(Bb0qSvVI#cKc~8zuhx;5#T{0 z0nP-drdo98)?#C{@gSaBy;zCcsey98lh%fT(mh2qJE&L%rw=UwWq(r($dvWwv+X)} zAC-IqQVA44PTp>ufJl_t^hy)OMs+{}*U~6mNm7uvl0-v@uzK&GX2JqR^fm!Xvv$LQ zF8A3a-tBh8c82z`jHI#+miYmxbc^Y=%*3Pj0IEjI?=Xw)?kWtVtru$xDT+E1$G zNM~|1Z$YW!XV~GlfWdOxky6O))-71;Qt6c>=GqjQUK3C&kZf4#jqr8TK$&y8x2Tmp zr^sPWf3Y|a;(jPL@aNc#)!hW0#T4K*AOxbctBKz0W55mivf~>!@_f1O$OaSkjOek0 zCHUA3<6k>0fEAhyiwaKS7`|uFeIa`FeCE+MwpqXpK9#oTNoX7N$Kg--il^=<)jVN% zu--Rd3aubQfV5C`PI4O>H`D?%Zv@JJFATo=rn7rT(0ai0C`eVouDq=wTLZyz+Nq8a z8&aN#th}i(g?C{mtYw>IYiiB^^j3%pHBiPtT{1|g#htRvg?KIkx{1~T<@O6_Om}W~ zj#`?^?b>e8YDFZa6!R#KL0Nl-ZjlPYhiWb}SPYpYLIN)0BabPeLmTvmC` zLQ1dl$aA9SU%DlL;^~++E6LtW569(v|onR^*t-SPHw7fNnVQ5adM7wI~C`pHh-KN!+7q` zm1B*p9J}8LbjT^fcn)@-YDof_1*Prek%nU3RE}%uE>WhflP8YppeYoOp^>~Wtc_c< zMAi>IInJh&#cBtnsmHKpj(;7oSU#LS_#)Nxa;`h8*x3ti#{@{dMb-vuGwkW5~kW^0NYj-1YkN!JPUvdz{XA`3rNNi#~ zC4H0-MH=B(?rEkKC})phivlk^stgBe49y-V z(E+Ov2)j{iN`0yMAbQR0*~DaNKOt{f+#m1vSbO3r)YoksK9Kq8p~06ns7yy#y@4Qf z<2+f82oi96po5h%3ELoh6yE$o-g=V!cxO^8tMYTfYGPn+MFzD`O-)Jnf4J27wPWoW zx4A+B9El($9OKn-Rc*Dot?d|;^={lhr02}D<6;2pCu67@1~ndG>BuN|sMsx2dhY&4 zVzoR=B_(iu;p+Phh48R$r_z1DeK$5jO2*oXcZK3MY%a7@fgkF9_XQNcEwumA-((EIXV?T=KU!RGQP& z4L~6HDV*X_A?kB!bPs1QzH}KjBkN=c7P`UKfPU8m-X>`&u*6kC@wNOwtu+O<#Camo zapOu+lr@1o1I&(MCYFmdD^;6TZbUVTYOSTl#fzx9sKs zFjO6M+E_Ae_2_$deRUQg{YdT}wXH@G@Uf3G4j)}ud_VGMta1^H?wA1gTJtSIQ9wA? zK^a_eSR;ktz*PtJq4UQYfv}4dPdK=J@Q4}8}kGF zu50s!9YM3H{Du_=y1+fx%F=#km~haz+;yDN*Xq*xPsP5C~U##&lfWd zo0+(Os*WXVh+RMNQZ@B)n%@erGCg0`@tQNe;GmkSg3VB+WxpOpO@w|+n_3rdB6&JP__7kQoJdn2xICm(kjIxXC~~i@a|0CkTO3nc`4?z=j8~c*t_5 zL<}`7&cgLqNHK^cH(!f79QXD-1}3!uC3Hmh9~xGB0rWqs?yR700li5&Q1PP&*(>M) zu9}cvb)}bI28#zzpevY5X0h?spBpR>K9q%V#@Wm2 z4QRkC6*QFkR9pHWLtfcPEBSj~>ws4_0--*NqxuQ9&;ZYEzR<1%g|8`uY~-O{yFaK~ zME`}X>RcL!Jl~pK_57djGmX4YJeI)z$cf!Spr)xWeG(|cN_aRf?8OGqh5XG~t5`R9_U~M%@K-b+(*+VukzexV{isHf$zp1x`0#te z8j@o$S=v@|<3GWYN-_kozk1C_*}GvtM8~Ma`4qAUv%d)N{(-6;#P&`2yLRtyWV`pm zVTe$z91Bk|{7Zxii23In$^QL$!Sx0lhv;gNvE$+QL}(IQKZnmndooY|$2pO&5|G#X zSy=o3jIJLaveG|DemwQ(q9sJAdJeO_tO%PMQfxhyULyOWHX!2#jc{dvsht95-sU@a zsKaU{E?4P}3gGegZNI$e{Eui6Sv}bi2(1x~{Z&pE|f4B#zLUWEg55 z79eyXg$|I+ko@I%=0<*uTM98CL2;~p`^s6rzEeICu67gHKSj_~dwUoQvp+2$?7VUN zomm^3x01Kgn8>I&;m=UkevFcn^N;5et3c2*@u*zL>U@Usw;>)eq&3JbfGfodNh5z= zv*dvI*zUu(#As&^&1q*TBE(B85jnB+I|b_?b}vA#(S{KK5&=}i5=UErJ9dHQvxJl!T{N>0r!fvxZvf=c|fwjil4NbfumLqoUaimzyspHAOzU*P!&@ew+W}FEWFJZ*Kc->!lB@w+cg46|IB~y!I==r;~jZ$l!Bgu(>Me~p!AWFL{dXY-ZZg`>tq{>BU0DE zSd;*vcVSZWWP*Xq3^yXMbw~5n!9K_ur&tfZ5AAHpa}EY%r_TE@0VAX?m^CxNxvmFC z6lrvVh)g3M39}*m#4c2P4EoJ~DMM;pkt!Z9Q-~TAqMorR({M$stp?l;Ymx{qo5}A{ zh;o8*9Yl5c#957c>?jDuBbgPS$-sOo;-(G0zCQl&=P$Drv7zv}!r#P0EhIXdl3GAjyG*MI>X*7$(H-xb_&8tlj z{q?-~d62bW8Q}@!32K|BC3ZmYr#PNcnS%2ODWC%c-)tVnZfg8JJ_ zq@|Ohq&(YKb=^RY&)hw^qXoYcvQITzn*i7-Uf2SFjM*hiBNZUfu;=O+$^^64&nny5 zdQilafizuaQx?ty1@cc~l3n2sdHD(4kz7Ne`T!ygXE4;ff|UDZvWGN%01XSA7`zzw zuE0?-uLH=*Lg>nKisX-zg-;t~R#RU=uI?NAk#sLDh}DM!SmHv!eO<>c2b)T9!O#;> zwTa^I+*_^qAE3eB$8Gkz-%6QdzgnwCX7vFw)!RtPYsHQzw|j)Xf(p7&Vfog{(7fW( zOpe+~Q|DuP0@oue71=;S%@%5<5TZcgVlJg>r!Ww6p>Yko8A#7zb z&tp?Pq+_Xl5z*j^7WF9C1KA0{2IbHn0Lvd?eq0xDq(`x zBj?)8x`F>vWv@Oa_4>7VYJ<-=h8@nT;!9Z?6=qC#+kItEXoWc5a~l^$Sh? zMcuid_4}m(gGFP!bwH1lNDb2Eho94>=8IRWa*IhcsQs|nt1SBU5P}7I63H|O+&I>f zE1()_0dJn!h|8Kbz6G$)<+FIgWEjwErlgtVe7#ZKN`m7RppG`XpNx}GtB#&*$t+gL z^uvH!;HoSk0~0tx1;tgFj};{~^f)zrZh;`sa6_Bh748AWSIOSouyxK{Hu6ep)jzE$6|J2h!H+g7Xb$=IU$tK+UTt&8G$E2WlE z?wnR;Lr&=jBIHL2{z&TR(i!$7sG1!T*&qv99J|DJ&ET0lKL*|ET@a&nZ$Y?PPi=_POZb3O>?{7O!I z`7#sJ=cp!sx$#{$(RaJ${jC!ZS7TiSR=+haI`?&yt;Uvh=uefke=~_+?us{Q%L7!R zDCS~Z(>kE=>(0@j8TcbSJ;URqY=|Tg6WO`vELP1R;a35UztQfzkwT8L^3rMc(>0>?YAC za((f+s1sP1(iBi3i>B;D>1aQ9{f8=`*+f-(lWrHW!~bX|^Y=9?lo(Kn zcBzTMZUew%(*f~GdaFwyPh`-_MKuIb^~y3I(%RnC{BF_6Ndq5MI;0;F(h!;vy<=b? zGhQEeF}nR3BOTgIxFI+6x)JiPfBw#H#giHDozP3b|2aZp-$+85SQEMKN_Q%82#Y7G zDm7qwl?8t7WB2zXLci{V2k|gY2h=bBdP+&6cs<4M>yDz;x~H&SISS~8(` zXgT=>NGS!@?eCLf!k{1~LZ^F*zIDb8 zdLmg?cphAVO577TrDjP;&#GjMSoN%1hVBnbyr(6zujyBs=Do@--N^*V*)` zkn(Iz0vW45$ooINy2)V4n8?*J{??@$`+kE`5|y!opqk+SZ~gZ(AYXVT!_XWRUx89s zEl@Ye1Yv=T;z(NAid(Dt z@uz#OiPoQr8IcI^TJ?@&S;E;0Zk5#vD7$JxPY9$T^1W`;)R9*NOz2U3ot3#0lH=iF zT$?4z+_2RD@j(0Eda2>U%Q!` z>u9tI(%8HJa*V^Sar$;&xL05ccR?eExOAn+rs%U4UGG#+AnS0&0b_RN-xdf8gc#2d zNsNKdYXr}pgOo%cp#j+t8gQUb_YSARkWP-OV@EG&xW<+<{>P zce@Cj;4gJm6zh;s>jCoxPM;i)!>q1(e|cHSRV!G&F#`6llw0!eG{3h3soUL{je8R< zA6cv&x^9sRf_pOKb%Z7x!I3F1-7y3Oja)>{6p0iZveDyBmBD%TQyNr4j@h(!0D`td zVy$Fzwj>iWF*`fp)lNfDkOy9&4)9s~4(E);xopgV8PbA7sV~nNR5rEmxEP(v%o4|( z@!`obc=xTxq0fG|U_~dl;*s5lW4xUph>`)esU4KDUEob^RXSP-ncsF~Xx-fFP7kf( zfr?`SX*JiXjVnDOR@G*Qkcm5k!p0A4sx={rzXb{wwn}rt(5{6Ca-}g`CQ4b(mvqOE z`ey5ry}&FSKA4jJg}g6W?%yqeSQg$1+(gpE>9o{1TX7O2E+ll&0`X$KGrcZzW#1+6 z$pu6=#u><|WN!tf8-wF}51dsUMroF6XQ?YocjKwIJbT-43SKW5&mcKGE-ayLD1<9^wC+M#!Fc^gWr zh3)4&b{1)SU=1bN-aj(o79G9=A=C_{6z?T+YbKFuYDyO7dx>037v`T90E<}S=_ zlJG6w?N1y17t4nj%cEXcbm$htUY|m0;wd6QVoKscq`9J1y%fFfxbZGh^_&F@BudTkR9N&Y)K9Pb&nb()^P~-D>m@<{*H%vGbx85;_+A;JaSgQw2<8Co6}g) z)Dqa7M}a5ZUzaWfB3;f4Dg%6UxQGNkIQWWUarCf+n(?AHr8chjAVyovo#kqjZ-WA# zz~ZLk)otj8yMKoL{%1lq>6r@>ET@ZryiDGH5-cR>j1&su+8kk~9F$=3rn*5RE}-4g zXS zG^rT4(;rT=mYoTjSD4hj@j0B82a*ufiKNYT5D3l^!En9Yy;AkDk}|FQO}=t&a2^I( z2E!)EG8kU;RKRjA|3M)h@(GhWqn*Sh8hoQo??2uinv+W>h~Z%jVI6w7D!%?eC|KX| zUV)i}OaRQNi-Ve9;FIJm43FirN3^0MVc z@0H@KYSv1+a?Ay|4>SG@k2@1h-%w+c4;c3Y>2GwJy!)G`{g+2gwc@}gcn3;y*|cFx zK3fChRd3`1`@#P9Jr-J!@t}Q?!P^b=2ZGmkOJ~9+Of2_0bnYJ&PSy_^B{@+cJn&u_ zZo)?Iu?@}&@)DO{F|qpGB=YZzdGBoRl1!+;!=xoBs*M}Z$oB?juxNqWm8dae;v#sx z=v9^pO&dr0+o5s=pd-Vf5r=M(on2v^nWiv_9emf3sbc~i)V-BQ2`MJSfuNha5w>1>c8c))ZJa=zm?SI!||RWwNdAW38Clup4#k^n;R%GKqCRWE2G< z@wo|RDHDR`c7O)RmGLGkFCu&=2)n}V!I$VRxI5>~niU1wTMf|gZg|ScFP~RK&+aVR zsx!M1aGRl7#g>ltG}UUEIjW3ii2e*rfJC!dBx(QYAw}E^BE&nm36-2Ck!(!Jp=-)~ zwbQrZ(swRA%mnkRh2MAX-#glH44ktfyY)HiC7I_pBGj+7?RTT@l!Xy^fuk>BVz!lA zfNYU}{cTJI-kMfB1BpORhNRkQL@IlAFbd1dx$OJ2Di0>hj|mjmL;_w zToRJuLXL9wr1Z%>8??iWO61Dh32Ta`6rDNu?~Vjqz3YmYgh~Fg|Ky%u1V6Y2&dk@Q ze{pmE_I#+r%YV)=v@)m92EIk|N@Nqo!H!?Ot_Kc5 zCs=QQe19&yRWTJI1%Faz!)_^g?c0DW6usm+ znU-n+Rj)B!j%10dlQ zKuon@UMzvk(-V*?E{+@OkEr4)$&FX(1#&H|eGguJ9>Jk!21e@*5T>+1r9A^ko$X1| z$I~IGk+5&SvcGM+4@0pl$fn zU8OjoE~I@x%I@yQ)a#xn(lisdhH8v072Erck_qth3^AIT_*5)I4&S;zA3($vP_pkP zmZm1ov+|EeR2L%`!IjW~M0%Ln10JNSIapIdSU)*Qv}y#zo?`iK0cx-P#bCY1sV1hn zkiGAl+_paHZ;rojV&@CE+JG}aXJ&`L| zy7gA1-fa*E%ZF{;1EaNd$3G%c*ET@#vU~))DI(|}6jCVk;eG?adPOxLMW?p=i0^ZE zOl3YF53=I{I_dL5_K>aak6OF|_QMSIaN`bQdS{=axpyZ1nDi0yjq?_QGbQ zr*{vRnU)pq9icJ5XDhWDSd@)j-CVD(TjAYN7>kHqsk?&wr1R`6Rrra}&!4Qj3CWMw zf4{a29({M)bps%r-it|neC+w%{&JpMpHDzCW4reeKk!ycU<2MG66o52?uXe>Dpz9Y z^!1u_7kH%Otk%Srffi>5r2OmvQkHHA{LCQK$Oklf%{c+MYb#%ia5JZS(yyO42NEJp zf#%13RA!hA0V6JJj0B1;?7hOUPKGc(=fOu~-n}LFUt3Z(-hbUl;2gyLg24GWdDe=l z5P8-P$9QI&BgeR~Zee$1e|3&;!+UQ1Hf>}wiM(7DU`L6}3aOV>5ZBBZVBzaNcqz_G z+~lZ)7k{sT69z!5o$i&=XY5NaRIj|mdg~7}eA3?URVZ@LaN<{`v zyG28RXE|MsPeXHaa2`#es%1$ zz}H=75Td!6Bptl+4zfKC>5%1uR8!4kk&QbZGvEOhfFrrt4_F5RO=_iUWV*hS^0oyR zE{p-&ca9;Ei#V|R3Jh-yE*RvGus)5Eq@|w6_OiPh(z1K2dkwIME@F^N%vZ0S-Oyuzu#lmtzil{a=CEy zSqQ2iQLa5O{FkIqQ@F9N3$^)>S(%w!28gHUVl{QxVmI*i?jn_$qP=#VMi07xG57r2 zritDm^+buwsBg=wuqXQl6EDpU78a=bi}8@G0oM{ih*lq*11os`9nQP?_XHZyy7u)f zSS(9vnFv|YL?D~ zQYXPnaYsgJ9S072U@m^)j^~6T!E#&yg>$%)yc^nD;K$<{ zpFUWgyI|OOnOrYiwE(ivn}6yehbT2^g%O6$us~^WM^~hzs^rHWxH=Xf3I9YqG;MIsb1aOJ5NqSH;Emh zP4L9F6T?6mc4HIKaV1#CT}{Q@(_Z0G;659UJ@jZyY+S1JHH1op3~yOkrBFS%2yqkX zAu^^G^aC8F>W$@90Jm2=0OdBbs1{y=Osrd$|N4s5qsv|Gx7$(&kXfkSY>4`T2LHa$ zL4`~}5IsI%dNKfL*6XD1T(|4zcZ)o2B`c?@Am8E^Is_&>5B$$DTuiS5wzw8}Dm>+9 zNMN{@QgI=pZVI`(>w{{? zf`Iaw`CA8wvFIY5MFAab2x4gqAXVb4>{%NQQ{LFcEdr)@p=jIVsDnpD5@4)3Cy}sjY7zE-4`}s& zH|2C93ESxe_8#Qw>a|$GE^;cP)W#8&-)+j8;rHNKjCF`I*IL&CG4X>t<_wUAOG+BR z8G5Lp@pEGjU^_N>+3kW0v9kHpTAIbcRr=v6I&J!pW$d+<&)d@=%}o6!>)~CRXTx?O zolyGdvGPVp3P=e#9NOd>epLu(`^2AJ+S+4^*@_=YY1 zN+GUQ6#J88A}^U}G8UA;7T7>Zd88V{4KQM&N?ED{HEh>;{pusl|ZGrX*T zQ~+!ZQSk{7w_BraRVxMTl1rG5F_1d=KS?%3VhMvn;(n3sB~^w;QuL3Nn3eftqr}A5 zN}*^5X+f_qiY@h71j@#BQJtkuIm*e@?rVcPG&8u07_x5eWD{}gs>HyW+9P-d2UZ{q znekPs`k-^StWDo}f{9!=I;sm)rWK)gLQi#VV3WUR0Pe#ITv}hvZ<78W&k-CcSD2SV zL`TP1OEq1>xdlwWL$+HFy$$(Nb`ov8qI0yN9C!OZ;R$xjB&Y-d%_s2 zkgrI3sGQz$jZSxbSU*Tsn#OZL#LMOQY|IJz5KHXBju9{6D!SP)trq&F%FDXqLKPp% ztcXf!g-W9=XRf*7^B(kVfSH}`a+HZ0(YCf(@U#HNlH2rIWH(gmOs^&h|*#Nf>np(OAZ zrK7BHkBah5dqC6?%gzd!w&)V!BCDI$`}X`&T$%|o?VS+`N)YPy3gYSyntzu{$5N_j z!qrO(>mWW%jPDb4dz=ze+UQH=-3`h1@sGY)%@pBv$8g)7r6jGwZ61g~<23#Umwgex zZW_=_MVawoQ;GHsxsy=I zzJGH2tp8PMmRqgg1`e4(25q)G*Qbt?HD-a%S4_6Y#SLZ0LpTLt*bSURQ7rf&o}!c}aY}5XX9Z=!HGBk*5$f7#XjhE^KO+ z@(j-t8vkg*8#XGm2A{HhSAi{{oOEPreW8n1sFT^7K131Q5%)EenZE9ys%>n1g0*-)BQUYOB^<9eta%;}HUEMrw>GQ1_YPh~Znnn5gQ~xA8@WJ&{QH~@}xWz%>I5aHlsdG*rQ>5+??<5=& zo!G3mlI-!`qr%u-O)uXu+!l(vaGXrQ=6MScy2FlYa(4)qUmeaFO-Nv_kd&=qy7 z&jMY@laA@!@hd-28ju)_ZG`B`^^qiV2lo^GC~4)LJBU82o61E^9LdKGTg`W0-7?1d zk@c>3@ka$)f9sliIv7s+idftR{D^8iZzpP+`Oy-8YE0KxomcWgSU*15C2tpbFwd|| zh>+2TWMW4(f^>6ojJ0=25|@sP{Boc)s>ShfuJW40C&!W5`c)?M?I?Ev-v+}+N>W_y zHmDg^fP7h4+Y2jE%k1WAegv3lpEFL-f3ffsMQw9{Aj!e-RD37O`$7CZ%qmr+bB@ms zClXyFx=19=!s<)J;#5psphhoF$uA{^E!R%;Xk`3od+kwbjL@=7U=ldqPCdi|X-M!s z%j#-M)u32ahhn;5PhZ9nYi&0Jpm-c7b7)eSrPIRcRJNXwz=%|KS$o-a1=rAT95m@t ze0QiIM0$@PVuMq5d5&YmsQV|C$7l0CH&|-3r4rrST7j+;eDjB~ znv1WBiY}C#)nJssf3HjY)T%-KJ;8@iPNwu`*=OLNxxAvomW++=%?RT;+03OqKUh)x ztdPz|mClN@xkmBo%O+XMEJte;hKrPp7;_?>F>q zNHQ=tJmbjcNF(+hz5;6#PAA!D3!f4==LWs(PO`8blvnYB(8-D8nF`^ocDJ-3&@3oK zexPA%pa6h88S+?-3$l%~*9(<#u}oN2wH0109?%LPVcOEiBku*3nu+7eZ}RD|SXSxq ziEEg#dP_J18X`rhC6X@>yBru|Ud`Y0cPR)QJA?B~iG6FVD-L-+bOL{b)XTBMKzGem zn(1aW60n2t&JT;z58bl5_AVrp+;C_>sJ`LDBtnUB!pW-U3qkVX9e3NO841Yd!Y&5# z`b$KSXtv8C6Y05bBh_HI<=6hi!XIf{;W7qp{5ti; zQJUU0xXBf)=1+F?{S-NGgvBv?&TI=STE!lR*`QO#hD3Ip@&0kb&rnO(2^pDz2`eA5 zGsCPWRC0$NGin-yu^c8Ac6t_g-dEgA*SFL9(y3l_$jS zL5T^{)-;|`c)sG$c3M7&18mZf7(E?KO#2W3Nw7l*EFjL37I-*9Ect6*@1gmD6C8Z) z-M2YIU6>S~lXn`0+@<aaVHx z1P843MKpW2LJEQSaS( zF*14*bD!1m=9?v}Id2qSsSYv`nG13C`D*voKS?_&Q8Fp`Y(kaI4S^?QI_ z6i;}(9n0h>S878nw*fLL|{}(etk_8u5%ey)LJ6S-aguo2dkaRwJsACX8P7)5l6Ki=2s4DJf zX#O?BArlQ?XE-tQb@*%8(bRk&b^2$%<5x7}@2~#@axwZjUck9Xi1FC1?b-L{?+;*Y4@$IPK|nI$@K;SpvIm+4rmwgKk zNhMUm5AHJDK(KKGmeI!ey8uFE15(;97s-KPKto?IRBBteddWS@DPUQ@G4~@x4J+Npifx)xfEW1IiwbPnm;u21L_LE)icFdzGgPHmxkat zzZO(R=mzOf*X0JiPZ30>8)_ZyAY=nKNNLY-aLaHuA z2di+H)_u*$1+)$_AwT5469+*}(K(Lmo3i8eWIQvB|Gh=8itVkD>KF2RHEGkI&%Vz6 z{Pb+e0a;&s44=RpXd94|LW>dta?(T6ED|gnpCDVkhQzj)QBt0g4-qYg3?M>Y(R*-= z>UO;QMp}@40H45Js7`PQ2a%$We)9-LyaxzJrS8?#b`K-ndTpwU#Qw+In@3Z*hVSDg zW6GF$o->Dt9YWhwrVK?H5<+HnBAE%9XEJ3-DVb+VW}?sfX_DpOQlF)LvPu1qOZK-f`X|6`(_k=nC17XeJjF{@Sj@nfZHM`W%3)XHSW)1_ zL_&4o5>$d{;9Dg{_dadD6F%@TFhBGv*SK0b^VMkw|Au`0O}* zVhQ28y#uWmxer`7I1Aie0?OLQfm)mSy*ixQ%wvtkyD9wynG$^#)a5T=9*j&HPuVNp zDFHn06@wtHsE@^Fjd^dbPaAG1oNQBm5Th<+QujW12HIpJG*^r#vBPj?@(pYpkhG*E zC1k5c))`-hia{|n&a0idG*qQ=pE)Bn?}Y`Nr~i03z!!mPLHLktj5NwcDlQ3@?w}M5 zdZPP^l&f|gKtvC+s9rI-o!H2>fSd6(&i0RwJ@GuR@E54;?!CpbKa_G<;5UTOlB}3M z84%PL>rqHE8d0B^O92j{7)>HPH)^qWI-fo%VF zcM4;G>{!}((xpae)T+DCYQYt4Yp7O{AQ;g)pAzTs=ZW$Ue~CGN$U*S^YdTU*_-TS%hlZ*x80pshR=jj=CxphvGH28%GH}EFjG20hW{EygqiR8tQ5e#7H-oq`uc@s+ zY$x_~EpbrIV=9ut@uh*s;ZK6Cj$aB2*(bxM|B@kFxiacC6RUbRmYGN_*+Q8L)zaOm zDfje!ITOLGSPXJlV<_>+Zo4^ z(adpbwK-?Uw^V~9ap*O=@K}%*S`*8)OoQ5l|_dro*4_n0@Yu>01I$@M68Ma2E{bMz7ZqRkYomGA)Y=-b;V?-`P)!B&E;fbLT!YYO|9W#sGtJ~ps1Y#Lbd-@@y8T;E>>q!37eKa&c2PLxUjr2Z zKk%diQgS`Q>g)aEKlts7x`=MZDyWMF{y-H2?Dkq1Q4<51HyqkmT}#|*Z&$tNO8zk9 z2rnoBg3R#7YHvOKkF`7iKa@98sFDR9WxKW)(i#1K0$~*tX;E2s7xNqr;GP=r2KJ|Yf^y@}8n(2}I_2Ll))6<&rTbaU}D(r>?-)&=E< z`Y0;tKW=;#(qo-uyt%Gr|!+2vr(a0h7S^#YOhB3Z9*Q^Z>K zRa=cAB&ksga$P?mQfrW`y+{->L8;=5!Q!X&oc}p6(1Q@g;p+hAId^y;KLUhWhS^!S zJ8+j&S*)O7C@Zz-sPn2ohf%%q2KZi`3)EuRK6o>cHYlQ@cZcn-Zv8uS`b(fd83tf8 z-TeB0;LpVW1%DcXKA;f#UYD!vjgU%#Eq)pUx;zlr%zf1L4I;rSrDp}@O*M3iN8BD2>)K+hMRo6C&+rh${X&{`}^Vf%*shnR$Re$?y;qV|E9Is9A%% zKo9jm;~6OD)F%hp|Ka@n<3SLl9~4y1bwOBwja@|z-!42it}P>tK|k#a%SGCPu3~H9 zqOY9A#GEmlm?@kwq&pxr+q-d23eHvz75U9!i$PF|<`#kIxg3;G@0IJ(%o!TH(p)H1DUFq$O|fWLLX=Ix^5`Zo*o~5%+jaJhc3(ZK8&kGb)-B=|BGAk;UE+8t zs(;6sC%F&y-CRm?N_uLN!J%W3eUd0omVUBqiez@mIu*YCWKpvTf+}il+5S)DCb<$P zp`i+r9hd&q>=0JhJ15Cn*|nr6@mrcOpkd?X#>j&teG?knJ1f#G1s|bMb3k-s^^)q9 z;nd%IBzh~tMd~^~otsN{Gyc&UtS-k%&;uR2dtT6LS%xlR6}*OX_Ov1xA83ES5_Y_l zo{3MUJ2=QB?fi%|BlI!M#M;`T5O&V?fu_nUN87RvYwtemOwaaUjT>Ns5MdVup?6Wu z)X_VwQz8c_%n7fi>&{1qGfwzJ=&=zZ7L1Mx6Hm58Zq4me|4}vy9h8kM31q5#Se1bR zFq4fU5!?mVVSj?pq4kD^XU}(k!58+Yk1F3oKjr!$z;CzzW18HoTp|>#*>!FOkd_3% z8>Tp|qX_)Ve`D&WZv2ivRRxSZ*fB5!cYTjqkXIw+b5R#mkF`1vY{ITHh+w9$4Pdif z0>|hZ{;2n*r_P5e<7B5oxe7tEA@jAxZ<jT%on!11Z^AjPn&~Tlq2ZO>}Jz_4b z6mX)8AuR?VAc<)ti79didNfl$t>QDtc(5LUaMm){lKqSC1bL-m+78x*+rS^l@`ZGe z9Ou1AE#~0R(7a45hqr*zyeW9T*3PlgadF9@Tmm`$rc9d^ALPctChr^#u*+yGKB4S) zU`ZMWz%m#V`h^H6rf+`lZe`-6E0 z>ZaRkr)6hw8c#1)#=_`3J~=xJ*_`sBM_a<^ND=VlNSir_oDb~7i0P#NOEUm(Hcpu zDL#GyQ3!}UjeC`pP+F+|Kw<;LH&qtVa)T@xg&AF9lzfv_5dAYpEqsH8jSw{Am7oKt zt*0(3ocBb)B_jeZb!IIsBDHk4Z$)B{WqANacY*>gmQ+pk8N+{UgSLo5Ntm8mlp8>{ zs&XiJyz@0PP?9-)GIoPPcXT*6y&;e+Q%Z_Bs2R~hyc+~+mSWa0p1OZM<~&&`I1Fd< z+?0vA4IsOl$wc}k(wc^ICDVuY%1ursYl!Pvf=c-gM~p&VYib?v6X_eLx%$)3IAub~ z_I7AT=u%El@w+hUL@6P&S7U1Y>KT+4{Lw>5zJSHKfsdQGelFEV$~ZVza_S9TT;hso zW8=lJN>G-&O+ymLwUrO(`B6Amg%5ymIXVu1By;;0nl;ijkje*DUZ~CBPZ{ z&N3PBDA|paJw{YD59mZ+nTSCYa49rM#}LarV3)@Ij3~HJvIpu3z`C~^LJ8wVD*tSsL@??gHKGQnglalpJIfK0JP?31BYhU4pTAz* zE3GgG6&Y+pju)?a0kS=Ab%OxRnGx|-za1*Wv3@~Xk-r%&|M8UZx95Qvbi#UAG!7u( z8mx7*MmV%(#0vGisO}BING$ec2RtMZFnE(+8`SN`x#}d(3Kbm3m=y5s)A~NQh^A|qqU*pS`FbGgzF^dVtf;9;H z!*ep2Zb}zUjBtZu({bT9o-9}6C5lO&-=jRqjPJ9%rn>mPApRHllm{VdOS^?a5aePv z5NG5DaIoud6V_PMo&|*9uuEXm1S`)@Gc9yuavC#M%{3C%Q>(3C)m8;lrS)mo=TF(Q@CZi9sA; z3Rg)m$h%D`4+P{32x9cn{DPttX1$B!=vDOvK5eC>WE0*DYiRm~3IjL9M&|k1pJ;ar z1YJuI<`8-{KL}glUU2k3O2W<~cp&IYW|9T2(Q_yl0!Zd~srIz)0H!(9FZ~5LXU-4R`lh=Tz}GCpxrj; zr%r?`{koc2nq#S+l69v0TvYHA0Zf^WAU_472dh02s%%0+h=p75>-G)Ms}DX>Jc0yy zz5utqjM5w^23-YI5J^}SWaw<$A)>H0a|VyUBw>q?$3lK#ESKj(!s;@l+tr#J0YR4! zu+W2$$^cw&=93$F5lD@=MWSi41BKqtpnV9auz2qPGC=T#ow`$)v<^Bzpx)4G{{BEZKkY^f?Z+pm<*XqGYOwZJu)_RpUq_p45-x>Q8K(! zYUY$C_|f~jbLT`@*_>Y=J`i`C+!?PtB8sNenu6R_FD7+cgjxUw=2y%f?}9*nX($MEMjsJnHT2Vc(9+QV6f^!|%+wsLHG!c0vrCBT zeCRaug7k+h&)L*;ySsS-JeXTT|7`g@pd&2>{ej-@kQj_zE&}E`lPBSHRm#dMaH|dZ zG*>>>N2L15ZjvREy$)#KwLhZE6<>{0ABWyOZ{NZYq;_A46(CJ7#g`-@qp8K7*cIBt zv5J?UXtB^8X7GETsHjTz1+2KWI6A@G4$y-BNt_7IiK_6N(2Qf23xPKDfc&S>F7==yqqg`ll`->!bgU>E&Ppx%+YEoNI20RYXDMb zaBZGmQfs-$#@>z~X?JKV)Y3C!!(Ay2TzYj`9rD;FRf3#)yL^E@X3XhC7|HB?|1i`Mq$@xM-7@sT z*EBqAG@!?_PFo&y1>l!#JP;$UrCkCv4TI2 z25ObB)6&htVTLLP8maKUE|d$g)5)cp^G7Bl9Vl2YeF6c;SYD78{<(B5Gw+Q=Qa}6~ zH-T_K1gdaB5M))tub2PB{p4OD+k-?9cC#q)MRXq4{9K}xr?AUSK}R7#DF)}9E<9HC;YiE6Iz~TxoT~zpuzkh869!~nIm(jeVvv3g7f$^%Bz)9 zbr?o7ECa>4Zs+Fl`2@mm?>?jxhST_osKFoVc7$-gf+za&dt9Z{rwNamDB}IBFs`x_ zYksB`RkC^Aoh^q_)8WeGbs1$1>l8FrdOD)wG@QOyPw|?n zp_ntkft32hTzTn+_n9CR=llM!P{bT`huP%z2ZKGIr@8U_F4XQTVuI7lsqq7rrY*lA> zAUBm&I%1bWXqT+JhiF0!jiRCt6n178MXw@iZ%+=D<|zHwg{2|R%vjRHbZd+* zK~L;mf;ox?$YYrw5%;7o<^4JypkE6a*tdI7Jo1c{Z~!Za<4c>V8$?>LBukRBQq&aJ zMu``+jy7deuHcp+E=gOu)R#iGE6DK8Migd{IJaL($y!`4-{C*{wc^T$Oo&UVUxZju zaJ50&D{_vkFJ<=>$+<}V_hf|Q1is3#8EW`&0OHYI~6-84-@A{oQAJSDY??=3fyEoA*>iT#nZu+=*W(_@1(sSmoH@~dOFNJUlT6n z=t%_QR#<%a_m1hwL-?mKC7A1lYL;o1I&jwBzsy*r`J}HFJZ@(fp5_`ySU7aSXJ0^I zOWWzzY6aY}^ax^y(9puhuwm7s27|xVQgnr)Av$$%Iv@cWW168Ubof%1Q7&+ZdOo<~ zLt*A3TBgERz+8Xlt79SQgR|d%FNdV~K|*Eiq5-U(_*@OB&#T$E-UmMjr#eG})j(fk zj@^y+l1S>Sz0r2`j$!NqT?ao_qh@N5d)YGP?it;!a(Ow|Mqz zH(kw6P_9=qXCTg){J0OvPVR5`pVW{h+?I2R?WY4h)`sN%3D~lNqk%7K9-6yV`mca3 zQ~`sOm$Ik>iOT>dWVyZ@as{}C1@)2I?eM-INaMS@itA@A<$&6?i_b1kEmwbX_owKO z#}vWQ)TJI7t}|MH#|h#9a!Did9MG6tO^`Q_X+funISNV602Z{DB_hxM7<#}`cSu(Y ztWynIq5je=wr9>|D;^yMxY-@8>Wz08s!?@@!s4*uFnV?8bdZMEpJEcE2vwI1JK43F zcl7@8#qYuEIm>y6@=c+0{5|3IDUt<-Fj1`Go9Q!3A_2>gIkxO~gsgM5^8=!sDD#J_ zx5p8DQ2Y;O_!>gUJ8S=@5m9H0N+`_pvx+qeKDc2D+fZ$2oYPDEFJ8g-pbGm$W0_qJ z-Xv&l=d+|IF{l(GXL_iDKM!a=Uc0|wM3bXnU1+1ZG7N9}m&Lm< z3X6*dZB*@4Qf2GWCSdT)5{R_ky6tC5@N5Z^;pzfDR^Lkfk7xT0p%;2JyngRUzSe@u z+3m^oA;tgL1W&E}~T(Jf%Z7Hoj!%_*48PDn4hd>PY6h8PZ z=ifi}0fhOVe}BCXPwu@W*(El>EfRtZw`t65H>7%EpWNe20?mt4~)R5;tz}Acm>`9(chD2%!3cx1hSe2SQQ{r1008sdWOlF26 z4bDfH+9Q$LVm)3J8-zt@*d$RiM}$_9gJK1Ie?>$39F)VE$WM(X28>|+jOt&X7`q-q zZ25ivKMcOPG%)v$;K1Jdq6;chd&tNug?jrF@P4y7HQeaL* z46@5m^Ho8%_AtEVD_FUOQ`cV~`UuD1G92co-!y<3>{x892V$^=hy|n@;9>n7=9qhOBBlNW8 zK70xx`3UhJ$q1q>re=;)H#tBFK$k6V7(yfA$z2E>&x4n~N9*kJ=^bF6K+1c|N7gtF zYL%_+^)2A*GdMOx4W8+f367;TXpbyu%ekB#kRKR^wERRVuT6U=a{im(lrTqHe{2@e zPmr?gq_7S-PaJ!KNMNV=Go;T|A!Rm5Bc^^igCj$AX{+yjWkl9B$J#ao7&hC1&$fYi zk4)QyDY66Zr4w+{;%{<<5hB~=L@V656$^9}w&qE;6or4r1?ZA)uU-6KwvSY>@JSrW zqimp{xboua7bSBFD7MR?0JsK!nj}Qf*n15cS=at>hb4R!dYZ-wsQJA3V`6JSnr~F( zh28~%t`fG};UE%fgsNNmWjxpVt29Mq+>9AAM3+$^J5I7uo-Lm7$EfS?Xg zrCWjf%B^VwA+~`JzUyuM_Td*iQzUSl76qwA4v1l9n(L*ItpmRxNPaijb)!J9)h0h0 zkkY+aG8Kda-ON)IAVFt-$MKBg-j+3Y-SA z>UFR}2!;P?3LuyWL(P@{x2^o(S)9*vxypH;!;mABBL`6~BMLA&;WnV>T1y6-ngddoA_}O?IK*XLjbLSyaQq^bu`Iab5VP7o?gN{iy9+qZ zvJN7LK3xNER(Q_jPUFVlHB&7Q9U|k1Q0Ii;;Rojven8zf#(y*rmisWGVsTVY55r%6 z)ME)56hw z|GW|pyKLMmL%eO^!P=6;LyDauk|j^SZ2+kv+hf{ zsTsI+_7F<2XBx9DHM&>07Rp3*n077cdnuxlsXy1!og=#tOr4leLi{j$UeERubPVDu z`WQxO@f8*{wnv>+`Bn^!lR^ssjV?66G$iYwRW-(mK4Kaar5(|6#+d?F#11G*WPaib zpNPSmCqe@)_uG+>Av{;$yIf7%Gt@`NnH+1(L*$PKX|=0^Y(ws)Q^{APd_kIEvC>e< zGLn;IkU+Gj8h+VB;11V&b<$Tz=|nK9_aI?&oFnTatiNlnquT$9LZ+xgCHIq}YGokF zZioHFHTHx_tn5-ri)(sB7&AMA>KueVO%=U)-JhDQG>7!0ZB3E5oC0I@^T^xH*la44 z9giv_$1|k}_0hP>w}^}2UE)xf8bb#i!|V70hS3FnzZR~zr`=Luy}H3+Yb(Rs%rzfM z$t6Rm_0c8@3zc50vPmlzjg&*{TYy}(hWi;JiHhUhle1QJ7Dmx`l|P2Q#`5V52Wypa zIZrDQ9val+HISbFRQrkmyJzXe&vHhui&gLAzw$#0=Ik+@W7jx8w%&kVRaQhEDCmt- zkVu~=H%kCFYZx)beUd(EMCS&~r~Dcy@734!Trg8n=%DkfXhXEV6&@kN2E=Y?xz0hbIMztD&PPF044vgiI=0tS;g%koV1Q{;v43tKt+E4qs zMjz)zD6ewk!U4sLs^aq4438w}S2D+2l%KmTgUC>hzuC^LIp@+cHJBGwc{i})EzgdYrwze8w71nkU z)HaNoh-3@AOx?i(LA`Kf*I)1WgtVf=?eg?sXDLDqg)AYS!Wd51G7(;WTlJwgtrCmQ z?bImB!!B-R`FzccI|;(qHkVqke`o;)hXgf~`_zZZF3&-dmvN893mvF*AlEYdb>rUl z^Px1!3zWyHT`ZU2_Fv+R2@Or{lmg)P z+{}Q9GF07GpVII*)|?tPg(n@(*;cpuqm#k|OK@v%fx6eF3q#QK7}k^*u7c4GR?y2leZljOx4zR6zg6J7S(VH^E|0h`$mrTZOTh_J)eU6`~JXo?7e=`xuz%oAj_)*{_5w ze?}51;O9{FdDjqz{C>%hJXk8f_0B~bAX1A3|9G=yU3d2>vOlC$B*-P=)7ZX501a}S z8WbA#!xUO`I72Q3Ol_v+Pu~<6A{vVFRAGlUr$3MTEQ1e?&|hVk3kgnMR)o{xPj$ru zg^G%ewSiGyJV@5$Oc-YlHCTl69$$q+G{B`^>2y<^PyUF`4NfJ#jfCOU<1Zhh{;X_HsNmI+ zi$=UGlKNvCH8LGL0`=)?=Y{H1sVm=f+txs5f<#Dq2V_;gM`|c9X#2Q6IPQJ!gN3c{ z!7}6a2RIK7&d4PYCwyOIUL*klsMHM_L|1{J@zLkdI$Bm+pP3c-RjD7=MWv>X%QFtk z=oCKSYLbSP%93yIgf;T(8!%I$Kn<1OOFRgl zO6B&uNbTYVw0Q~AI?8z1K+8{oQh#0tc?Cwmg*t#{Py3<)4(`* zPfSFg`Uut8c%H)LzsekTNxa}mdD+v?8OZn6sc#XgMP8pAtuL_(?Z$Y4oX7z&@goDO zjLw#HmfZ#zGYS!3WmQo>OK-^b^?p;Z&bWQ~{Q|_Gx50!~N5IK%)u{J>&aoj`kxaxX zcSyfSH^_R358*V{)$Y_!XIxyH&{p;SHpL3S9d(yCOnd;YP?3Y0q@6?ZEN<_(ukYS8KQm$|Mbh1n#s=*@ zigFgZH|O?#wD9eK*xCYAT0Ynv#akb3I)1>>@B%bv_XBSY~*+b>k&88udQ)b zPjgj_A=-2(J`tXy8m?Y)g5%w{Js?A@c2C1}YDdqmRpLh07sj;%2+x278Q2MhZdD|% z(K33<5X!7Tr^XK8!}|IALt?wXY7|^c6-|5EK+vzOnpbvFpxH8SI$xJnX%2)ww~&M< zM8bZx+Hv_vJ%D%-kqJn?%Dh_zmF3ISo?lA!1mxI+_KenmFh z4Qj-_RbQx^a+4CsvL#}tXGr`q^l{Mh$l$V{sfwN^$;j>)R)0ITQnJ>5m3JX!NNEmg zd21*pGlAw{A9~xB*9S3B4q5vn(42BL`LtVR0hEQfgSs;ASkWDA`JZ`A`5xCf8dZO6 z*ubH^H*y<9QFR`&9;?^AV4mCV7_qkvU%bVs2}udjZFbSwDQ?WHvUb}^2^w>8-BRM% zboMZOZK5E!OCoPSs}rEnnY51@pj}&65=xWynO^|ik4)ZsXa8usT$K7pHlMk;l69fQ zF2F0FUGQf#foNdm_U9weRE+ZB&^b7{^GQ};6BWoB=En00!bJC_qPGB7x{>bqoja~_ z$mr78o4Jr?vWF2Hx|FGMQ5EVwqPFGk&hWJ7--mR0crUV7EAe$GE^%M}P@J)3Uis${ zi=4ax$enh{F$PM=y^w+#yae%Ul|Xxp!0b@l z8rPI*kkv$vL&)jgx%Hb!Ts3n3N3&eSS?cZpwXpd$0=S8_itKy6+?*_YCncCg-MlQ% zBjWRWWXlf(i&ll~6V{*`ILiMded@+xqhX34h`cXN&a28T#|Hw8Iw{>wE+VN9U+XOS zZwz=q8{5$}v|3byLK^Pp?7An?w`4;!fZqfCCare1$-zhX@G*ctzd- zUDAay*njppfS$Ms`m63#-!REp5PeV0K7>hzZOP0xxq2k=mKKbhjFK)Dv?NGFXx_URU{3$qoiNJT{# zFkcjRc^j~UBx?Z$=b~F+hlrQIo-=%%Vn;FtIY#fFP9MR7O3i)xgtsSH$qc~_#bx?c z1W1d3v}hd2WfFbIkNKO@!KN6YEK5FdvAQqy0!?kGYuPDh68YCZoxkv>!MuTOf+rA- zBop!(?=2BKoAW&zurq~cKHP*>!&cgn%o`U~a1pnU$@fSXTrM<>b=zGfFVP<@@y>q^(Xqq+Url6V-Y^dVMxUP=L_Bv& zXo1vL&e|o4VG2FUT8faAbJNnH_B}3Qa~(nFrUrz?yhY#n z;X<*H^LXy@I4CD$NRQ+(p*?O0%i;Gx{3dYme!@o1S`_9dv43Fh6HQ(o8`7ck=IviiNU_C`f zhms+*6;`)m3Y8LKIv-RYpR$8aKQE+E7|1u(1r#5k1{ZAPws<26pZJ7}Y>>jJ=6&8- zt-vKWVkt;!`tB}vC+vC3F&%m}3c0TI5Hb8UhAJW3z!XG?P;))>R5jwGBNxM1Teb!g zc}EX#0_GZp_?M+QU8txFZKwmpmghfK7h8WneIjm_o2f1?x7ncO|~lH@yYR>oIa2qyS-m zj&z26xBiA`?D?`L;}DbvJK4Dl!l_9H2> zm!BS41D;_gNV>5lu**JOHA>J+=1O@k8S|_ib z$3+a8Mul6Dtt(Sxd-vE)D)Dt+ot)xv4l{r40n>7R?W+MZ#5ivhsPI%NowNrweU_6) zT#4EU@vc%z%D~qJ%4S?CYfNIIvY?wOh?r&}+uS$v zW6NQlqHZ#5e}S|ocbeGx!TTF80^CwU zIFx$N&vpdbo0VLb&-jGS$68>Wu*nM7l`E_wzM+QtZ74;SO3&f3D5^+|4cOq99Ajf6 z_J9O*>PjiJNIBQH&!!PG^{jo>J;1lGPquO?yvnTv%FBE=-3O8I=9iY?p3KoHu#K zWlRCT;Cw*14=z%@&;oy+9q`m!Y5fAgkw4>+cF@)}(=p@6jY$GxMtJiSs6dNb<5L1b(5)Nzia19lw}eqN{J6} z#j#30>Ck!-khl(lJHkV^GiTN{g=R&F!$*h9uTRe zoOLdxEKzxl_G_ZNphIXYOW8B&FNXhwah{V>Bvm4qAWC3@98WRwr}jdx$F!X8CZYee znA+<>^aE{E7007Jl&l4&r3Z%1d%!aOHkcpFh1Y-dj4Om{+>HXbKAsplw40yV!=y@u zvT%s*41d%ng-<5dE;x03Lm~Zvw14J55*;1xFrOFnmFb-#`;Pzrh(YemcOe+aR{wty{oEg8MahWDz2zK`gZ$5XsDT8Ms=j&K)- zlUKvNFvKjH%Ouc4_yBOLS!&kuVltzL4Hk$C!0~#QzhM=LCKjA&5 z5lqDIa)KaSp)ObpXY&>tAgS`6@sIk^KjR{-GwRZ?p8~vZz~_t=m@QZ0%A^(xo;(;%fzNMp9eTc&zT&at5}%Kx76zfBof-NF z{sb`59?QqiiD)S8r0gS9;WLU0Dc^aO+9v$YOfhIRL4ekErdeTi)$WElBx`0p*Z(9P zaUSG=KMx-VvB`c01R08q1*r-R8I>`tQFt59#T9zhz718~p?u^lMb&dHDi4aq>0y)t{)he$1@M&$CkQB*$~?VdBDYM&Pf13AIe`$fM=a6cJHF z>n<>gU|%!QIe*4iw!ayb<}e*u`-l~!higBbqSm2>efO?T`e63@R_$%f{ReB47N=;k zB@)-^=Xe_?Pv8$7YIg$L4ze;BlZ71LC^#RJJ4Z!{vWN^foTHsikpIF+EjlHGI$yjD z8{y;-*Mfh30Cha3W72VQRjhN^JmUU?g_`|-4E#U2Cf&~8?iV#Nn0EBJ2~(80@ZqsktymIkH1 z(NX82@ro++l1AS&1=nLCt+$ZTt}h;@{6?2no`bFMP6sMFG@m#*kciyf`W@)^SU>cK z=>%sVy2FEai0sT}lU3+y{1qiWGCAFH&IF3p8QZeChzWg9AG>0%bw(P;tYr)c(J28K0fvUg4? zSDjy(`*2X8jN%hcKg>%~KGYFQ!p59ha(#@wWa>M3n4%vw*Q(WhW_OlvW@<_~U7AjW zf1hD^+L`N%LrJDBceWd@FMFi{U6Fe{kGsvYr>eA_S;VBuJe@ti4Av_4I2wijLP7Si z(^JwY8?+;HUkxSY19gXs`&{}>4}6Zdt~X#X`L3)Iv(V?qe6`*Vyd9yQ7O9plk}YxX zo^vEG6Zf>AP+Xx|PawZEolG(H!J2@Zt~N)DwGT2G>~9bEg3uBy zwtyChOk$5=a&9@r_%C&w5IW;UJ|bjLc!;1GiN1YWpay?wlxMeMNHZ$b`R&WItqq9& zeB%R@*sHfDLod`UD(U&f;ZY3Hi>UK{P-p3Gbw^;h6@U0?j%W&{1vGEF(IVMlA;Yax z4|C(?cYT*KNQX78w)dUpzN_BO&N(8`cv8Raf~0`{Np)^?o(hpJCy(yHNvpmQowx#K zJp=Z`b0+?c^3c<+sX*>OW@P z{zRUW)T6zZfBNJcyJHM_Dpf}4nF|ZLSc)cmK5jkn9Etu~Vm@xR$7Ynu31ya_h`3<;WC zoWK5NMAtFl2fMw|TqgrJjcbHtG&@JG$lzLfG=0?NtBh;iUdbBQoqSD##7De#&pft| z6$>4-$%&`R8!~o_jE^p~9wcU{nUGH@ov>j32uTY8a!OqfrVkTbh`8%!wS4zDN#~Kn z#6J+2)r3>pm-2LGp$3xk6=-rBQ)|^R-?z{X@<|}Ti zuYSUb;`*wp|FQv$0-HY#up2+*C~65QGrs#jdJ-h;#ty;^#qeq}i}7yG@?5Tt&aZ@x z#F|zwE@Ec8pHy(qa`dO-bF+Y(19(k}L_f6kDk;~vs9^wG*xh3f50#YG)>&?E>+stow}-W_fn*2=VJa21N#Jhg{pN7rLGzBIS`6f z5sxaPspV~J$n(#t1+4ElVo3VCq`A+&3%if~D|*NOB}v|nO!~_=F;I6E1cw|lGDi$l zskdQ~H0wUX)_7UbmMz(TiFCDo644s&W&To}2b*7&~Zv%UF5b$ujcC)SK+5(-cXI z7cqovB;HL_vhPa1r>OVOzrEBfA=E!84T7rQez`{a$%o8cZ9Q%J`$ZAoSKyUDqJ|-) zX4;@SaM!y63ZtMOf@d|GPr?znE;k)LKPcl()p~`=9GrB$p63J0w(LA`d{DYAnnyo>Ys{Ruf|vT^7<<2w z@fAJdxr_*$hShK|O@?JMlF1b%w`rKmj0_FctG$PdisU8V|Jmz13IPR6knmdpq1riW z%1_t~D@yN^*~A^Wz>Ru&oA!A`lnN31h(y}5H+cnt0=$h}v!ppo5yv4BXlZ@GR{1E*ML#$w| zc89J>y$g)r?6P``OmDl4jPL`E-!h0uM23qGnPVX4y>@N=tC{bw4`P&=Vq_12kt9SG4TF+pw3!DiQRP!$`+QT~}O3hK>-%tyVyj z_8N58O_(2^wxyC>+547P$hIlv0o@cJcEC5a7~-p%R211}0qQ?TZKCZPA|TGeEOy#~ zuTgSPt&AbV_z7eZR9$bv`v?SdhU*)C#|aSphu5=qDZHG#&twmEucI&wD0t_fp*8kW zrra?%QnJj_E=N+E*~qsr90`W4q%Cd>A4hEPKp0C&1@m^h!<0IAB+_NY@GCMP49P&+ z1W`?mZ#3Jvi5J#U)4y8Mue-r!Ugs$xGGPHCo=m1|$s#5<+NCpbmdD$#_BJGQ6@wCN zh`XT|=jTiv1B+e$x5e%|Cr0##7T{pv^P^s_amf1G+`WNn`S91`=hP`A#<_Wv9hHQ2 zlaN5AyeUR!DRM4^#);VSJq#VVd5X^z$zY0)=%Fla-4&_BaU!#O(#RjX#9lfr^&N2> zne2y(q&TxuMT*yTDsZoXaCsSs(mQ38KCy2_H$sVwl94ofj-!Z7ZE>u&oXP8SKSQ`` zgHRU+Z4F~bkR<8LWtQrTqm|ENYl)*h7GrNK*BZ~TiQk3Ea+j+eO{z10xkX7`-d_wG zlyzYiw+uy0dtLX2%P-r#e@eOTKr863<~*|tsXt!_2^W*;8-T7|k!$f<1gf+Y1|gj# zd9yPE&!7xZ`j`lc=f-alP$g{%emy@p0&G8(MEe@rx?zKP8MU{gP3!1ghbAP3ZJ1n= znyn~+?eSfW5QR&jTJ8L>303@k6XHTPA>pZq#lP=MyUD+8;5Th=$J&OKC>U}u#W1NQ zN3oo(J63{5Cb7BYtOHFc()n;5%fWOk)@?fSOdT7-%@c)NHkzHL6mL@3|H!`H=*LJM{ZLU@~@q zu(wOfP`E3GYn9#a3VqB$Nm)ib=CMeru5n**4$?-PMAxz&;4~^`CmW$_!8dJ7yb6{! zlsVh;wg)WYNCwo(%aHWP9IIO&oz7KbDKZ+8yQ=azT)STL$XD3pP>X3x6%I|c!TTIh zo$0x+Y|1w~v!R5gK;C5izmBa37ck<&(uwmf^c`ng zbA~#P@=zCpHF8BYl(Fm(rDA7nVT!yx4VlTQMT;gL;y{uXl7`%zs5LDdCGV_?mK^jW4UWWKogQ-Y(Tb z(kZS?44qAOeS+9~;#>R0Q5I{&S20v(+ONc|EoGX|Ox!Jmp$zfq#Aa`Baj6%^x}r3d zG5K|~UCb+B*4?3g;c3Tpb*U5m3Q{kO2lIyvt)c&zO&zwkMP5wJ<};gkIEoiF_cqNs zo>$X#yp#+cNfHjmeL2a!Yura&;wxgCWj-8+{d_(tjQmPdw60wK`9~*}`KA+>H27|z zRR0kFJ*uJTn_HctvVE)f`tZtbE|IoaZIIl#IzBuZP{qW~9ftL|jjR#uX zWLBn>YMlaa`dC3WTV!t|+uubmL*zdvna5^j97vTxtR{XYHpZ08E?SNw79A`6@ckE9 z&}drSB-+$ak342E@i;pjAIZy?Kg0RCk|$Cokvf~~V@V2KU5WV!tYJ=kR{W)|tj;8@ z`BAV4(sbSqViX6w{KQv|6>NwtlZ_&d7nd_ z6PNL`y6805pP2SKtj~+s>ngOyqI+M(IQKuv*E~NFow+L%-V#wRXZ9>Aw(}eG41;M! zyI8r6S553)9F&{<9F~Ry7Gd?c8xa1?lz1mRvSD^YHX!rt2Ql?G%>`(?FjMlovLg$k z)LDnQQROr*l}tN6=Ee*4K=MzWhNe@rmZSKRXy+$Ok4u;1n$^!w4j8=a+1%88W$y%v7iKKJ8ljI^y3BTmJ z_PCjnH00YmSsy3#TJ7sU+`q3S+oh#k689^FId4YHsG-0T^DR60+cV-T#rT5L*FRlC z^SF7!>2EA!R6Ju>Xcc~v_kN*RkemhQW~;=+-Mm6UW5Y9r{iGr_uSs+-yxE>(b|~B% z(lc4_3dI_haxFfrRR1}e=JaaB%JN+nUlz3$CT{*g>sFb1E=eamKR(p-3+phf(gf!G z-8!h!{JZ`vjVK8FyJ~o#G|K#|H0r#A*DoKkUdwN~lRY0sAX@G~eN9-{?A5(u2bX{; z+G2srWkXQsBnWhZ+ob*ZYCXbRq8SAN4MBK^oM4f$gj3YgEjB5-LsC4sg|u~dy<1v z0Zsp2vfx<=&hlD`eWm4)ues;yFS$=yx&>v>$943QxzT%P+O+%oSH@R@#Sk>^CfL71 zus2lRc8+PNtM!fxRmMoDvBD5!17#eiKlM6Hpp|cji*xD679^J}%rJh@XFB7Egn?oh zLQ-inI$1Z{^0+?*R9FhU{cJRF4@haU+C6w z{ka*BcD5S#m)qa6K2~e76h}>dgdtpfQmLY1$Y_b9XudCDv8f3+A4iCKJ^n@-Ds&}} zZzOzIb5qdB&v$P1T1cicvg{L7xinxEb0TjWh6ro*%bZx?O|^)vKEp0OMUz`z!x zaj)j6Pr`y23!XV;MubV3Lu#7XueMuS68J!y=%Rt z7>czliVyoqXOIO3F@dLk$&L}!VOsl=4{l}dE%IKq8=<$zSLVBB!tq9pRjt}e5A$vO zB+X&4<99x7(KO)9zk9DPVt0;a^Wnq}zSvt@$9qpQyM-Ca%Tju!r;lCvNjaj9NBe0U z#*KX;(9_(KPau1KYK(M%;SOrfa;jcB435rhH#B<-{>dYLkG{~^(O;X9FE(e+ZRf`O zsRmg0$J3irEe5N(`qA?g#PK-G-MEZ-^rg8!#d|Y?{>=}x#2*e5h6tE*6ME1Tda$R2 z40J>=O!uvw`Pj9(Di(GaRC%tcXD3=#ECryF=$0$Q1};O=mFqRdOBuFMx2n({Mf8ltrLD^j~b_qs=m__6QVV6uIj+)EbN7d9ozK=1FxU`r&Yv!gUnfImG zqXmb_U!8{Vk&y8tAH%T0B&j}#lNd=LH@GzY&{X_=nmiS_OV~cEp9Pu*+lhV~~s0O_Lw6|Fu&>8|2$S14h(pQkr_C;VO zR#Ee&@bpd1n34fx+A?4@;lZ^Ddc(lN+i~YTvM9)((GEQQ(Oz{OIpz@+hSh`S&|7Z$ z0n^ML$`7!ed4zFC)tXo1)TUm@#F?uNa8L$baO6JYF_KnjHKE#|ed9$iz}b(G4rOuW zakNStUPs)q)|Y-eOj}fg0>Yzf#H}8SJXd!)8U8=o-UOP;wT&A;X+SAcC6ak8Lv2Fa zShiUT4V0nSrYK=&mXu7H$COQNRLZzTnM;L@h{{|tMo5MXnZE1R-(?u{nu)( zSLeLPe)jX+&wXFl@A?hTJ?ihcA6$};n0+Pfgg5D+j%S{J>Y5`Eh=(X!u~h+i&)7Bo z>F#hH3rMgf4=K`cEZXL7dfc3Ir=-7({;998FbCa-h5A^x+BlDmqD^zr%`%~*-_pLR zGi|JNEIocBw$lnWuZUFJE2S*Yiw@z(^Rzu#1RLTh0crM(>R0|LqnY`qMtla;gDDNl z{f8n3YURw0_pc!_LIHWv82@`s-yFbiLTg%Y#hT{zDG$&o4Y-re*SNm55jwi*)OnPo zQhI(W-~GTHI*5lnn{y>x=@yqBV%Vf?F%9C8Wl*TnTk{T-!Re57r>jN7BRWIkjJV9s zqZM*CKHM(a1?S0gg5d-_E^qAy4GWRX7c8Bg1tBfGR{}~~1%$@20a$Ngl_mF6@9pAy z&${@!niX-a=?C4zSrpI|rJ}ChD`0lD+5}JHS~Jwo*$D`+XMxyQ%KB}N*9yLwdxG|5_yv=K(Uoc|nr%1<@-T7$ z>j|wLNa^0<7<%Cna5Si*KN$y5SDRwqgIYya=ZLcM!)&qZ(kD%Fq*ESQ-fO$C+;-=L zFdM#5Cp2wpjN0i45Q5VOQ*~C5Beg^c=9lMMw_ey#-8rZ9!yT6Vn z3vk-RnTyfazi{lIO5wpWXY6~=OCy70)=Mfiyds$*)u&mI^!&tz2J-6Gn#gJ&yaLbH zQ`K`J2CA|O@7)8xUJMhMGApstFA<=3J%0#)Hn*Z=F4S8~dgl4Hy?c;$>D@vAHT{Qw z=+{^mdzkcM4>~Wf#QHB4*2c{V+Saw75F1x`Ub0@d-s7@AmjP#o{o}X_k0eL>0*G?% znAdxEC6=Jn`d0GCTqw# zunW8P{%(27g|PAd2&sGX8?2aBy|tSZ6`6;38(UZtZyKOO4z2n&F8zGFY378=o{&-O zOymvmNqNQtTlpMA{91TVhK;z9yt;xC^JQ)^w!l82CYaDg*4L729=&*AdJGn-I5 zdG2}xP7o6!B9awh5tzOIRO5`a`7Qchu||4Uci5&`5@7SkOjV7iK3x~6(J#?xf_zQksJEVz$gj9A{6eTH4Rm&KWbgagw|-`LiYo ze(3@mqWzC{heY|WpV7JTi7LAK>&1_+)ZkTSp1y1_9iY7=$K3fsgJ6k0!?-X(U-II{;DnT`YFQ*ifC`Lag21sxf!lMn>z66;|rg3h%1*yjVAbSxDJ% zWOczG=P7s(W@%oxc$TVmPb#(q-{YGI62C#II0*){Pu&*vuIJzcNz|;GyiwueZL{6& zwv$ieKFB@c&?4|~Ctdtz6W7|am%LthdrblZadGJRNzsTck9g|&Z$^lJ2GOfwJNVQ1 zaNQZ^VbxIISn4atEJYT7&gn=W!8U5-8oA)N`3u{g+unc%&pI08V$0;R6e}iKg|Q2s zRl^qV@#Br8K%F(~Sd%3Ucy|jQ)KV1+QK))+;QF&GwOWy)_a6E^=G(x$HJYmbLKgRV zhI_$DUn^{*hrhD5UiM@O?oBZgiO-J^jTjKA#fIiP8|30;q8h5_0#t>MlOyCC0w>u4 zWUI-WrHH?+vvL%qB$2Snf$8r2jh*aCn{h+N@1nneE9N>5)R5HzNzSE777iaVUJ9z ztV5dMn|SjCEy>^fwAW4iOZHlx&Q2Z`t8{~?cRGHgC9l4(Q9>LMPG8G9dosM6v{MGO zully zuy8EmjPZuwP79P?iyEla`%+w^POxNsEVe8ia>Jq0?$nCXE_VR0fR4eVD~`bp=orK^ zUk=oZGEo(DeA+Jf(mYydjz4jrx5lwrXS~ujf@#kQRl#`efDl(!VzeaxgN?1M85WuZ zp8GQ-Vga`y<+7PQu9uco8{uqDvt-Vv+jl|#?3sKvtT${=upT2ZU?=A8OykY|xDpQg zUe@@_fMArEhabh;T^Md@7&#iiK9!Ons4Nr`EW?)^m9mwbSM0^QkaKl^dT^b!?MubZ z^7I~q=?(q$%2ar%#+lL^iUB$}7XFJ73eg`@b-QEeOmQ1LoJc6a6jAQ= z*mzD|8z&gqI#i18YH!y~yTh+7Dq% z&x~Vp1|7fe1xws8N}I=2{q9_y8z>2AsF%K?bET#l4ARkji827rl_{}df*SMi0lIpz z%jiILL}bLXPCOfg@6?axQy#T!3VU!}2?KK}UdM1Z6U+`y%U z%p=1~bKXnhma2k=w!_})X}D^9WLL#LJS)#d3_o@jlhl~5uEkaiQ`eO@SeUtH?vm=DWs81WY~-W&7w^D<6&X;g)hpnnq!8g&n={tLZdl0v z47>l1qe81^u{2}~r+=WlHn8=XaLsb$9Pi!MXBqL4=1>aT^qQviq^L0!4o>@$@Qph% z;Dv<><+8+h7k$MC7Gj{;%LQkcZ~^m4qK? zG;Pyk8ly}fkLKy^#M_Rg$~Fdyw=v3k(#NV3B6F@1xb^+@Qan#{9#k5CA<46PkaE$} z)8_Mt$F>IqQHNwjjNMGd zsk(%0)T=tQmKTy}MOuIkCbud*nNB!3Vynrl$*BA@&v52w+*QT$%Z^3tH3i5NloXOz z-gZF8-PW&}@}XDm`Ss(~*Gqxv5GZNJd1%UwZz8TlXjUQG_DPUD1IRWkS;BtrJTy}# zD!0OKt2J?xZVXFi5k$*_9P@{BH9Z;f)17dFt*?iLYi_7*jm%&fa;;OFQrRUMGSgS0 zC6N6{kmo>ry3S(zF0CNz5CN?4#%tS@cajrNtF9BPtT^fPlkouN0wbl5R1YJ{L!(*7 zS`%fxoMSGZI|dE*(34FlZ+h4Qc7Ge2stJ)xwEKiwuVFn#kA{kEqc;Mkail1Po{Wtc ze8epN1rw)cz78Y{XXLm}%YA-5%sTW!3=l&Dj*g!AM`gOlwnngyC_Ml6LBXG0ZEE7u zKhtNMY>TG{!7$^4<|!w7Zu9tB`_J6-9Fx~-t*5D$hTS8<`!cvGZ5b-_0tOL5qY;Cq8Z~0 z^6nWj(4SP?u|G-fD6YgcQDzY4ogU;s?>Vhz_p&!`>wWI(xMHu|4HFW6!VHE|%BFG! zKrc{7Bo6!{SAA80 z{swv<7&2D^bEU78o^Otx^&qWQ_1K-ZayE0Q-*{~@`Gn>!MYgg`sW!a>RYGvELLQ0t z2?vT+-d(+2-}3Rj6A$OYaaQLW)TbqsiW%YaS&~xR*B>B^``s;-+s?r&RigS0BYg=J z9VcNN%N$xMjs}70bg}=?z>6M+3VQ6)1j0?HmqO z|6Y#|NKplvupS*&tVgXill$c2NU1qLOmCFV|Cs+ip5c3|f0z_?Z7h28_OE)%2`_z- zp*c*`51nCW?+w(cOO0N0Qy`ZjH3D+L)@4V}-E?^GYiGI_%nBat79=j14Iv zfDj_Aa8}h-Q~P}A^&>(wY0u26amA?!HiQq?mhDYr{pFB6&*`J>NfAcUy6=Cw1bLuGFZQGq@h(ia{BAHEjS22fv0t)G_RI+&6b6pkRK2}~M>wW~i&eSRmK8e9jdagVXxTCpNI7>nx1T_dfzmCm0#Y`|0{ z7p4(y5R%qcJ>s5fzd?eUxIArt5r}q-h7~)8I6NUO=R3JnD+aOGX<a9GZO zKhka~MpbtcLW7FOm<&i7fw^H)gYiNyy3!g)G|c%jR`Yw=93lZdiMZv~@8M&)4p&<~ z(`nA!ieDQ2!>&~O?Rohd3}>#VyivZ6`-n^~mq+6}-hRKE<%du?zD5j8G4Qj{YZ=tnt-oiYCKM|WAU zA6=u&&uh#bh#sb^+4v_hTC?m6c5ivJ+yrlSykBaiCkrug zxYs_0ys_r~fB8-1gYdC6&!34gJyR$Z@z?rZg&amOo&x)iFZN3l(_hdsR;a!Qbt-3}4Bo=ue{_8tC&D)<+{N}Z)%BgGSSxnN&VG}j2u zD;c0w)D=#+&}0Y(d{=DtFgmM$IgvhSLJ;;3Fk3UuGU_IF#o-*c5QuzqRvG%~j%0>B+ zO&KRgqV;uh7h%LWE3-xl;U0|R`QOG*Om2U}DGc^tuATjQYB%$F{Y9cs|p-4H#Q zPf%3jnHufv{MwwV#Ui*B7)GkoZJ=FVh z(FS90K!8!^Nb?dn)mpC8f^;G5YN~iU>C-GkN*!;TLqHu0pkR}-8!!PggL>nFR%8ji z?_+{F$XN41^1C$woSOEYe0=^kI3m?()FBdJ%pKqq<{}C7G4N1}#$bDlR~KjuwgDYy zi%}WyubOTvQ%|cMLgtXb2r+JQ;a)nmZ*Y%gj` z9YS#WE;@rRn#_Jp4a2f3$j$MAy0;42;qIyN6u2^%jZ*{B1KMUjpBRwi%QCl5?#GtI zM4VGSfL>Dlzi&x2LGUdO^F<8{cB%;W*$6^Zho&^oPBkEJLYBvd1! zv!0w1si=d9$_35tf*KJ>4+!j?~O?eAxwT3}r-4|i)kyWoz$Zz4LtEAI-v zruy^W&LQ&FMP2A9P?ZCp&PhAc9xu0Rhw#r9@Mmeeya$P)|2)WF^=E^)XSo-V`E@(> zuffHiDJDGpkA?qZ87j%ZrTX!1Vte6DLkANMh+VSq{`NY_Y#gN!F9+0kFASL)noos! z&p!i#w=Hs-D)~~r!MRaG&|_YT{T+RG5Z+8}fy&XzPy?SB~6Y**}%cm&d#nXr3tv=Nf{Qi2q z4NTz!A}1CL3&WH!BquNygbhLxg)K0X!Qo&u9nRmYu_Q>_31uciUW(2e$mdGFRX^5K*)CBpXAUgkJVb0RbRIbanLCeQLte9Y%U8Im z3|u~*%tR3XXBtDfI|T-QC?aK8+49_-F7LhVN7>W^XLI2{`RmJOA0R3ri7$5P^p~AWBHes*e2u zP*-=x(Z9=Sz5 z$MPP%uE^FDx$S<1@R4&>^|GUKh=0V7{aO*Ap+w3(e@&U3dw!mf|JR%DjNTBR3E0^a zaBWauC>-Z?+T?TW_JOOuyoSJnsX1l%n=?L$F}0pw0DsjMc-7Ovff1s4gyJ^B2(k0A zNIY11y+&3v((8JgPW$h$1hXQEZ^$>)sMUb2)eHG~BTtwqI9Fhx^44go7MdOlM5c+q zI0-(L+g;?S!XvN1&_6?WG3!4_w0+-6+hp%;<%r7hN zOtl4f9M>X9O?)Q<%ci$_2Uw5)B90roJ>w0PDK`!ip&)aPkR)$?Dn`Fxz-y<)PpM1^ zWWARDC{YJ(bIVKMjw6S`63F#9rx1O82iRrqaO;iu%!c2t>&)m3^dCZGG~JQ9t50DY zKMM(i$4cBUu=qoO0xqPej37Gn5gbe&fi*~LU^Cd@6kMEf!4I|>$iZODTz%C~`nV7| z;$`3mlvTr=sfKWda4#x&vIU1AldR1m(j$agw94`jfirTT7939UcENVVyoa{_l+1mW zzb>;{RN2xsm$<9Aax*|MuYZZ=<;Vi4mbb*Iuw>wp%9umJNdIb-J+d{A*>$`Quxc;a zg~`_&<7L3m<#_DoG&OWqq1*#IBMu4C!hh@B;L)B{8fC*Ts_wIm0E#{kKKpqja- ziOMTi^$l$MYyRdGr_;h=wAD&o5Wr5h8NaE9+ zBZtu5{l}lDuoKY5TGhU5+(_kOa1{kHrNMb_)MO3} z?TDL0;20ozCdG!4VM&)!i+M|IiZk*2-A1K+sKPfFphiph$ zPl_N0_5x<(ksPFx!dp%+@DLt)BlH?W{eyuzWKQ{G>^&^RhzS+Rat?)u@J_aUt*@UC zDcK#7ig$MpsXhFhr-S#VDFG=SH0*r;3Gt2^dlbBKq6#@U=%osj>l^d%R@riIZ~k@j+Ko!AuIop{ z@%Iq#U94vGaZjjIYZ!u|J{djd?bGT+^W0E10{~&#X=Sq_Qq`vf4CA6RRYcrF(q91@ zROt1}8t)OgwgnOi1qGKDr_0)b+%se{q1jo1T}oP-zgy$iTVvZR+GoBrQ>j=uTwhf> z5atjOsHtJ#d#B8E=L8U&@YVm9%w`oDy`3)5Y-Msj7cwN`(;5}MbUB(jTc(+OwD+lI zMG!Sw-zj)~8)nu&L?Hj-Hc$VA&@{TOS&2EW&zXrRpQI*;e@@DASVQzMY8}G2P!)(^ zlUH@$-o~NRHGLH#3d_BtQDK9w zs#pPpXp3F+ zSX$$?Ct$KRE9=x>n<4=e?hhZM-}Qx+A%;cFPE|*;%RNXeRdS{6y*bd^wWHcCmqn8P z#(BkVpDi2%w^C&3qqDOxtY45I&!_7)Hyi)keg5O`=NHHBuTEi;*KEH}ID7w%V~=ZK z9oT}AC7kTu=Kgg_oq;8#-*XhN=HWqzytN389W{hc?v~4&N^KHr^33NpSemlw?IS3SbcQJK8ur_2`a|xj6SW9IO z&OM(u5HQc>n#7O8$onrB;->qU9uZ`P=l8e@Y zwwJdw+e%!gdS*Oz0XlJ`*jjHAhQ5%|cB z6`r^jtgS-$+>-Nbgc|BDy$6SHU*1mL%stWEc|+R%^UOWK@O;Bi6->G#(qQ<8v8v-M zKUSi$sZ*kS!vBt-EKyz{xw|mWto~Wzbd)ipiNgr27Q9 zq)S#|uvTV{n_oLv)^jR#iw7Nm*aV z{cKWe&++le=GL4%{?~M>8FBR6d|xqMmvzZ(*TRr>-^Y$;%ytL~wnII3oFncB_W1#g zJm=kiwZ63%`5xL^O~nrd{dv&w9PWTN#nNr<{MRh+3&&9bNLAqYYGEx#=)!m9Z#W~m zM)R1T*CZhljD@Uz)I>?aPp?ob?`7g12GC?PU-ZCKyU^*VYFZ;vmbcJQ*-7=5`k6f5C1sos74ty;)G5v@H zo=SIUJfSFb1|X^(v^wb!K?$K!)7Rt9bUe;EnsMT7$@?60l&7Z8^(=CLZcUE~@mDYB z$IBE+>b}O!v|cNe~HudM+uDV_rVDki{}} z0=vvlB5T}&Pzh(CF&e^*01mMQUyz?|zCeRya-t^1GGDq@!k_%uXH2vbl)5j^5Agn$ zEdK%|eLQ&qf$a-eCn|8|v$#5Y1I{XZ;ej}MeX9gkktHK;QnR1GgjmC3`cX+LwgJo4 zaCMxxJ&KEkLS+r+NMN1P?$2)n0Rz!~)|ia5GT<5Obg=HMJO4sC`L7=d1dRATb@<2) zuRH%2_!+Yj{50(kW7}K3^LVBmREI96<0u3*<~$@Q-+7rR-@fz6y;CMOCqj8AmPyk! zi$I!ggGlrBCexbj6@?XGBZ-un5}13IFK<}D9E}VJzCo5r37LJ*_X)koOIRMKo}LrxgXv25n5DJY=8_uh2x=4Y%Y> zfgxx+xcaAS$Agfy6@$iE%qffVGBBF_hQJ@3;58?3B5k^Rh!Y0HM8w#pyuF1s6XR&EYIe&#xkn&EwV`>)lN({VP;f{U&JEPrEZpxG4ck}h)pdPWxD zhjfUhhxthRWvwG%LIjcG)~M=;oB$1`OR9~m%V)bsofnHh5xWz{ey+_*=kyAl;k&GD zhWEMT!oaJi3%biZ5=9M2TE6+GkQ4f$IXdO4!c)-bNWIlwMuXW&!I#~bJv43IjA%uZEu zc%;`1@Li$ULN9c_d#p}&lwdkPCxI0X)S43XF78Kauh-riaXzqnvfM?JA_jM~d;6;c zCHKzhL0yuBNQAoFCffSv!35v`SS&wrD2N#%8k(@4W+tMr1f;*>^W}GRfTXf>_H`%% zXu%62-3-evE(}8h<5)>nw1O2naxXd5QL*U5| z0S|&EoHP#01Ebr^w48un;Mg;!z}|}g0nVY5v`!=|AUjZ}`n3+gJ25A4M?xWC9dy`M zD0UGgvPfN=cSXAHy)XqU0g&nFO-Y+bY9i-!hGrx9lQ&B$1Na81a`~go|nkY#`$MVi=?vH2e^blB>Oc zdFlr^s6T8$*f-rtyer<>6a~2dZ{i2({!)$!WiD??ZvO+rg!QxFpzeC7UdQS$NV<~4 z_kCRJ5ANhI5Y>;L=_)7na{aTll=tf&ryu%`;Vy6;6JjYhzE2{QN>M+oK!&A+2D41W z(}B3%J>kQ2e#!2CJxtK~WzYE5^ZUCxj^N-gw||uo@Md4$4wUfoB5$MqvIu)Oz_a!Y z#B!iiaPEvrMl_2k^sVwh>UA7X7m5Pg}VPKJmh;=5eU2A2bQo~$4 z+b;tq#626?vbL-Z(>|!skicA$nC7tMLK%!Pr59@<_kLsQV@IJ+GQNG^;2WtOSn;H3 zoY{dbVvzW0dH(UQZO0LnC7Eiw!zz-32RdNfcM$kVVEp$MW) zy^!7oyPojjeU4kS6FGl!0ayXyUd_K^jjd7KM1hg@eYL-=v8to6z6;n2)+xi0`HtRSC+sj@~=W-K7q=i4{U~VR+gCI*$xEe58O_<-*~u z2&{*Eh@ZEGq7O`$t1SkQN&)~4i6U?vhY8iFi@DOdU&a{qV2ocL9xO?oTaLEs4Obq9 zqu>#6n_A%%A4bI42wt^9ZN+c!*g|AER=ENy(F$jTt*2YZgX7{wV1~Ql8*+Hw0iE9z z$XyEdysnJ5N*pxtr>*n`4;$w;o4W;jo^r=D=7Et&u`%4XbL>#uI2t<9E6!)f2gQ!DjlUP!Z$p*DB$=48!1F;y>U{2BgI5$yCdH4S>~2m}#N$ zlFq)q&C;VF&3s`ThQIY5>QBhx<9W38$F$qoVY$gx3}3S>Wf11>T<-nn3)kuUOwa)8#EqF zKFTe}@P+WMUc)CR@y}7?zwMNp00pc)kj-GCPR$ok#y0@|!so#J*};$y5bhdc4p9YN zz3oUvl|lgxls%kwzpODL+!2J2)M!Xf)%z~(ZsI3A9oea?{Houu%ussnun#pyHnK5} zQBO?}_Be#m!8f<$m}kI{Ri~msajD-E2cu}yQM@tW48-gMcph6uHzYRl;!Yjd5RY~F zY$WZ6oS_3b@r-1D?Q$^KDHU)jqLbPfv4m zYo$?m!94r1V(xHVguFgYaNY3(czw<^Q8YlhmVP8n@0`LgOHeQg#lKB~i%H=kqw(%8 zIX*TELWGZccdAxg8-&Yz#`Dhe+%)~f7=|K_ApgrEpj=D5f0+O)Doc$1?;$(e8rv7IBKp3Wo9*aW{J6wB0KC2BiXSpy1i9AGX0gLtw zlae+I(Z;GXd~;DHf;Ra6i2eTQ2SVilyw_=ag=9Q}<~;S@u#p-oMuhAMe-YrDERNsB zN_zON$fZa`YFqk=ylS!18M8Q14NIO7w^vs8Nl~>5WN90`6^|Qo#kfae9t^-;p$!o! zhN`yE&7BlAtQNMVaz@3f*OM_M+n;^}GLfAZCM3LhpV1p?-nrXcMW-TCE>E6KKk=9v9`yA}2V0XWM3O0*=5UPld(sJoeFs*VFm58y ze#5VdUp8vy6=+DF%e7{kTx02RC4uI>e}Tn~cs;6l!#-v7?jHU@)6yhBb<(=s-`8r& zU`X>X)fU56RG$W~`Tt^zA!K~bV3I8|NV^yaA4QzpXR4@hYq-@G{|X=DsJQKgnZH44 z(O{9MGNs}jd`o~qTe;QKj5PBb>CK|kb;w5slS+l?hwSkzJmHj?3AWbw=y&`>yUA{iVHX?$ z6Dk@neP0kQTLLP*1isK%WIH3*Fxz4twoh1f>TGXIvgqL^hOw``yPQ;Gc|ChFDq)bb zj}rJLHCU`Q`8jd8mGCBt?3$Y0Lw1;~%FV%*v@l(Y}?nON(6> zx}Vh>d_;yNx8-0aIgK6SG6^;h)G=fD!yp5+8s9N4=ri%&>`aNRR++p0wvpw%rD#O+dc=M7^_RILP51eyFXSu}k3Ef&`F*a5ENQj*|$6r6D7$pl+t z7$y@S*EM|cH`Ud%BJwH|!_`SuTMvG63^pb3Y!KGErj3)+3*E*_*;{ovIA+TXoSL#} z*M_z4%%*a-UWUMNZEUgxIDCA>9~rOg1g6|a%`Lq9T4g2U*OmRvALCtAYYm%HkbYe= zDzLtmal|806i~$I?(b$LzP~~>$t;W&w%1y>SNi0Mhtn#>+bV02rAxB0V0_D`>p!fS zR_-SaAn6*SpcCf7J5M8@Tnr%`RLYjNHrs7e067*q59+*vbU)#^6@9<&h7tH} z)o?C;p^n>Fy_ksij@+mvz-f*T)2sgI?qU8dm1B%gcFR-EDNe`m$V&X!oyZ1_v?J9I zc#KMz(ue0LrMIg(zgu&O93A~?P_wl`gU-;L#-jo^90-;~>W0T3XP+}jMt-V)8EM(m+?2lq3=9sB9?X`^>&qI-5HC1;M4=D&%5AeO-5;$rRrOF&WX7+vC2I@ia zpx-0`RkJHQrp+VJFkg!;%M|+ySQihhm3W)-Ra0f)JBq?)n2!b=no`64g0HL75GxY= z&IU1?Bt)?h^266OG)`zH@|3jrOMqX9bHqzZV&d@Ys(sMBJI=+dN66NK5xz^@`B;*18b!>Wh(b)mF=~E-!T^0%s||Y!cE$#x9U=E@IKfJ zULgrP=P6I{bTlWgXRn)g3f+5*e5k-Cb@?`rnW;?)dxRsuqt9L{wek*NauF%4)g&=D zi8naw(>EJ_ z-9>ekOQ}GAjVMMkSky78d3UI;Ig^hkAL0)kfjJ%5l?iR*ngdV?u#-M!_cUY=&l*7A5i3?)V=aoU;V>>^A}!@mZld%1Ko6eL1=9D z>0k65+SfqBY!ByFP6rG$e%s}5=ok1DBlk{E>zEbCThH+2jgyD=kGAsO>hF(r5#60H z5B9Hk`c>~>Irg6$mUR51+4t#2)m2T-rUL{$voO7EMWET3^qHbC%?Em^K{eM?aCW4A z7Gjl}<{JgD_sjR1b1s@})XD(AL^M_z<;5CG;_;|RM-4c%*JOyAF@*mWL5@@G!4ZxH zlU~TSkd0*WJtT3Na(Qvz??DScQ-LA?UL9e#E&qg?!pq?8%4Kio!U-zBCtF-&4zJQ6 z%Pat9jO3f3 zR4)NG+ObTdf|QE1D?jd@7AiJleogP7vgxgacV~h(^v16|y&UK0wtXhS?*YKNRENkY13Yrn3R zv)?`}+ne ztAyoa#YH#_WspZ>R01&94q05s9$Vg;K0rP?NT)WhJPYPgA-?$Hhy>HhS8e&{Dr0!_ z4MUAr2x(eTWYu4#G%dIGU$LV^@*}FawA|DJO0Puop-{PT_32y~2yHDkxxR0}2(4cs zs0FcC!tz(_w-HGIHP+TYK6C8PEwTX3V{7(ocrbtxr8YvS&Ir-){t;n8EHoj`g1q{| z#zioBK3_%ixZL0?QF1k>)X|>X_a2U$0+w7O z_8ea;G1Y_STmQTVg3I^7^1DK&mn?cnZtS^;{;Or~snVK8gv4&joB6o%U3g&*h4c&F zx*Mr~be~Ey%L5GoFl2%~`XLJU1|hFCKoS(p+VA5q9M=x`$ic%=Fe5o}4vn9;J5)c? zNErK`|$_N!)GyfkA5F9S8aq}__R`kbp^6JhOpVO zYXz1oLKuJC`NIVCzSb(xK@S)G-vutq0Pz?*`Zd8tmZE=DZ9t%d)nm!w9Ie`|M|f@;rrm~;?1{%Y6~n5*e-W8&B{m4;Vqe5pbby^ESpEktD@YCYLKg6k z^GDhr$=YNCVtAa13_CiC9z}!=w^W;bq1yLhdcV)@aE_S@*dA*<9Wt?LH)x&#Yzl_S zma3|N=jNh#^d|6M8-k6i{QBTOXuG(i1Opdi;Sm%{4dweVQ0X4QWvN|#CclpR8+Z`5 zLepXfZ6e(o64I1Rf5NReI$z0vztWdCg@3DcPr=)`?%AF}lW}9h3TW#g2p!sJ1rtuK zUPpJ{(c#O7ry?qt7!7;CHG=m zF0A3OvL9UzFvwb9+eUJHHZhYtuY6#|-4@&p%sa&F_sG6XEo3cs>#6d#j!rmw zLLajd7ipn#s8@iQfKor$GyHpSDjDhu$Y-9yziL7B*IVb|72Z%O-j@risvlEflkZbu z43^Sp2Vt;t`v!0GM?C_;gct9Y{1v!H17Ws;&IgX^Eu(*r%~ewTc$FwunIKlZvy zG{fkGuX(^T3<6IX1|piU?6qrobpg$LiyU)djFArkbd~PYpU=XA6Mc+>OSA*n77}Vi z1@{4l<97T;KB|7^Mjo96j;dZYNP#x?3j8?67k(b&oO{vgQ^%bG{z7K06n}pELmP9% zMV5symNTG%=lCE5#PPXNEwO^<(9qyvrhlf9&+RIab}E6H^QHAW9j)Y!5Pa1uvJPQXfAi;1EWtd>=+8R*D9eFgE;#ge0f zg|adXa>@fM5xF~Xjkl^GzXN5lH>`O+OAYi@Sw617*`FLgN)5|PMH_C^%s58^xYdZ%o%-BXw+Q=u4+(!FH2T(q5>|p=bwj|XpIONn6@q{9c++*YGS71;&i8d z-_k^-ZP~mPXN4*H2|tclsTvoI5;j%4G`J1i_AivjQqCMO;9;TO#6B?9Ukt3@j!qOb ziu^htuT;=QWX=f`VDCb)pM<7!f0<#b^j}`P!S2OHkhK=0SutJ&Jrxz)8YMw+g~Tw0RDzbH)`lmdT4N?(N=lpc(NAsB^Kw1+Z4HS|a65wNT>eeg?qQ;#|Ny+R10 z{;>~v^iZ9 zAH|1t5;($UO+^(+Ji+sq^N(Sfp>^C3&~l%lWe=BdwKYIcGy%h^sfl{UqS}jW@w0Lw zPM{hz4C9cG3^Ic8hOrG{%0}nAqrXcXc-#>UY*GSg)tv<_Q+WUVq=0J7iH81_M({>I zxv(q}uHr?^dw}BYY~K~;!MwDLOOr;c`i3HEl6a?~$N(Kgusmh|*2}P;a(@^+^2b8+DdvK0hvjr_n8tsI zl5_@OBK8PLlNW(DXmPeN8aE6HhV5#fK_!_TrGpi=ZQe9~K>EFF@{S8{bkB_zA@TD5 zP=0MMl}zEL=En{_3ET9TeLT65;yQ%igK!RJX^C$AtkW0|LL#V7D;9*BIEZMwhABte zS{9>I&|SFPR_1FkwD!II8TPI>T@4?o__(@QxwJ3*RBZje#o_v>P~Db^1obd49s$#^ z>h7aXAN9ae7wQn$tzQp=yg^$g2LwfRBkztG2)ozq`zX_(5%}Eb9Ef%bQQfWK3*d#U zjVz-33D26=r@CP{HI44<5&#HFxQ)%Wa83D6EX;?EZ2?w7q9a5T0FJLW*WU*teGnBG$9lWemJxL!D*bC!R+B$4j3S-W4_-l75 z9R~zn)cDQ*C7CwZ$ zR%I7agO4nZL(;&qS2!k99#Y0fAnVt;r{$qdRLv(8J)Z$Qz;mOIK;YC8D$`BlQUW+z zQDa7MlJ^qyAfennFxy|)U=UG48JYyH_{4`R^v)B>!J?#Z5WnF(al3YKpdopriZ_hV zJOlrvBW^MqS{1Mo!{2fgqpMOn0mac#I3-`)hFwRu`Jd*`O&K>KB>IVkN zV&{t8B6<=b+;$Fzxaq)bICu6uav*I%AQQY!QqtlnvbHFYgXo0|6>bclF>xOcQ^c0`+ zr*Q6|H~XnJ0z*^dND7C?Zt}<0-+2|DIA<})tH>69OsY&FSxxN7tm-H-1dJTCvzx|w(#|v&}#@95M{(u>?i!8>3h+R=t zo>d19d}x5PM$7~FE09%j60$0&qA@_X#`VBnK^#`yT`o@EBTl{!Q}$0y>WIKbG0bEU zf1l(z9tauf7AU8A-)WlF6%>Pc9tl9`mcHU_*X#V~GGq+vIt(@d|1_W=5!UljL1jah zfa7>U!*ED?A&k#~($8hskQ14=mViEItu3Yr+ieCz&W3K+8qr6OBjadJRdc@f2KuJ) zd=C^VOP)}UrFM7rVaj}hn4JXRb$Z7n_&8VSLv?uQX!i~jSu{?M^&OD7KC633_; z93k9*-|4;=ggfgHE&}Yh*3j#Hpm8C=fkdmTGNHK;!9NXV_}H|E!0C+3Q|EmUF??t$ zF(qQ3x*sQIBkfmc`r6@)d}j-`j%iV(h>yG(1K%?z7}Zx~P6!8`hkZDv-73URgZ#<5 z_KJc&gaL6xmT2(GGE)%8M0E>MU5zj4_|`E{o<00NU%yPZ>SGS+&~oTRB;Cr;iJrXi_js74sbs0 zK>DTU=6f;z;Dqu4BfW4I_P}$s>1QzxHUTd|%~=0p&wDKP!==?`K|0>-5ovNXPgbv! zTs&ww*!|*KPY}BI+W#yil}PyHyLT)t-NkWJnD|*SM&`oDDh~UK@n6MURoC+)k!o`z zd2Z7=ykr#S=?Hc>ioqvN>PmVQlR)vEoU|Iwb>-;cS(bDO1XkSIqu6+DFsSZ} zQTTB*l+Ov&X?(!9JtA#?q|~H{iNfPhm zRWOgB1z2Q$>ncE%;Kg~4&kJOCjyEwDnyp!el}IodRTwzM$bYE^K%60(kAUU52KHW3 z994hI?Dl}r=N=(@s5m0qBr4@`T|%?g>h9H!UURZ!3(G3n`tB3rA>Wbd6zo)Hl#5)T;>j-}R+zgOZbYNJ_a zgXlR<0$7dnj+Vlyx{PL$z1-!qp|YRP9}Cc|%d>-#meH{exJwDfng#m4f+2a2NAlaN zae_lnSYfoDdgxpK#R^9-qj6=6o{-n@j`ZWVsoJ(LIeNSxAxTr2P#&;1<)OIVw)`)e z58p?3Ta4`EjZp}Xn`cZqVr78W0jmZiyPDf0#IpUO{5$!Wpn;S_bpw2&wbb-;S0xTb zgs02**$Ug%6x@*$XNaOO5&4WGdiURue4qGHet$WO#=-I^TXgJd4B)H?mSodLH`AdL zj8!aXVKoAV+IDrz>oAdH)m@1|UzTFxe}5cLR1Xg~dOFIHGnG z&*Qj$j4~TSBfBUMW0g4D$p*m8x68R^3vQ}8N#IGAVTtnH0htPp3D4rS2|TMboOqgL zvZ6hp?682*SY7;p@1Dz}h=ut%VM}%VH8_kMd;l#{{PuWX^5(7>O%ih{j8ZP-P&^H< zlzPp@2G&7^^v*)S$^nMydSr+Mo7$`9uGbj16nQb#Xt#z|T^N1=s?g)kQjk5d2T?xj z4f}?*nxfxWlfGUAK~M%z{uNj<`x5HFtE+IB?piItR^M80@!^1|IB34UEb%j1qGXQf zw<>f_rGmr4dy1h8_*RgSu)lhy_0jH)&n++w`yhki&=y2nn+2AmS%%}w^zD(?F$LLB zUTCV0L(szTO~SO6!06d`yi|SAkL#0ii>D24E5K%X__%7%PDv`J#H;x{Y=42|??ZE< z&!0L34i#(6>UCe5H-FLuWNr<#jGBbl5BWManoLCD(~T-ThgAU)y7?y}bgKmwN9{p2 z#WBc-Bh|q2px&Bs7$NDCBLxF^TBE>!i9$eMv7R zfs?fzX5@nn)vtn%65uuX=uwf6bPh17HD!&}aoX&28BT)PGK<^ME_OhT)ZL$Xb6t!) zEU{tMPqZ;N;ZyodykGu-w*(<4#l+)-rc2-Ard@#<+gD)qqc1pY2wztb;$RDuZ%^c5*MN(IdS1=@M0#cY22t{-f)sjxQKx)u9=KnDE zCg4!7ZT$F2D(#k1NWw5=3ngUVGK4G%SrU>gg&|v{6k~}QgUBF_N-1lKP-IsoTC6GA zM%fkFfA^z$-|D=-|L=cY=Q^iz&XvB)^L?KC{@kA>BfDfm=k)&GvAd;H?aN7dE<-+I zZC~Ve=%^}whDfqKfzY4WL0cs$`+{;{{};(cfESTs$RDuMEQpU}9~$-9e06yL^@p-U zInT2UQkA?bSq|DOhPqS}y$1YL3|WqEo*rs@4S1I;w4;w+8z`5as+MTtC^gZ+v%i#S zJe9^u;jn$J#}^ZGA>_79*uSeNUNoGXJPo&kt`^OZ-vd(XyVJ|>{Shi%qyHgvQ8FDa z(%V>JTzL~T8uwfnx?5gfKT>725VSNMR0t@Fy?|hYE*`kI4P`uX2OdIow3c@P+7ubT zucy8=XGGW}L>&i#W%aQopOvE3iiYk_ay_OypPV~mH_8oJ6pM1teJc>gyH1Fe($oOG z`Icj{J*uGch}7R7u3`iq0FGsl;ont)0&+lD*?V?dTUaAZi6@IKZl>JmCxP=&g$#2Dc$yE}UjWqy3BKl*63+ zP3%87Z7@!#X8t(2t*8j7vK_ty6y$6*LF+wn3NG*-T;PTSvXhcv$98xICi@P&@~Zt zzH}NCGqniBKpL=80DHZm`{@8PqoF6GWuD!>;G5PC$j1-_s}%wy>@({QAy~PdG{u$_ z{}H(-gSV~^0j#or@t;l@a-ays9;Jl548-)cI$OSK3K~rdXv2qL0FdvPdS1qM(4u~H zCwO#N2PT+&glMqR4ffL`?;Ggv;l2?b)e2a=r65w+7Q)ZwtW)tR0mC?JHIEM0M+o6O zkf4$xY0!KWkk|*<2ii98{l46HrZNT1^ld{VfMLLL&I%&w0n#NbaYsfwK68gDu66oW zc0xPcyBi|pBS!{yF$?3jD}oZkgPoSt)*gxvucV(<^dYU39{T88)%K_j3O%!1mvY>~?)r`%#LED*qf{vID7 zHlcQV${&7bPal~@#n2yXIM}XXmnPBMy!EK1El^sg7OLmj;vSrzsKfR=SaN$Zd=g18 zN6$}n0_5|ql?~ZS06zI)+O(u}9?rM#{(a!bKS37z^1KXj`zdQPg4=GBSGlzpWNri_ zo@uOD;hEX6_8Q+sGoy3Dtf$`GAtqD@ehgj{KpO=t5NXS{j6P^>z{ua6(Z!n%b%~C4 z3CK5G&qG1DoytlF5{yPnhfTk~cY%-fP`B0O^yLvGObdC_{2#GIa@G z9x|kHlJ6|DXqY~R+v6*MSa~23Xqf8sG)Qo)RasPtPV?&}9&~{M?VCTW&%PziXK!FG z)KG?!Vvv#7HrdW?qea@rm7AuQ;M5IN^pI@gpoD42d_Z9bJxhbPQ!N9!+-tbS_Yosd zCR;R5`N0`;%p1FC#gl+l=Rkq?dQROQOnRORxWX>d5@R|JK1W-4(}#e~FKI-mHU3V) zH{-<;4bu}l2Tdz$=s#5@~A7y%|Kj)p}jSF*p18r*U0;{M77e@5={wi7IeVsE*zDiCX_s zgJ&Ri2TdfLJ`ZiS@#lS0qK(jyj1Vz=M8eQb-W|9AB&QI+qs?uoC3C7aF=)PrNBp#` z-N-e&tL`_z)8=6DcZ~bvM)@yU`(%1I*J)H5mJIMMGH2-}%};l9Ab&FA9bHX4iBt1I z)As3#%j*?a)of>p_^O8nw8)rINsB5Xj3aq6W#ss**S%+-9!urs+q&XV&j+f~2cMpe z+bCa`P-ZFf&4*5}tJ&@xDCKh@)0pX9@;J;WK$wfGE~QE8 zvp$ENixSaz_Cr|To%1{7gi8Pr+;eJ}BE)PI@tCe$~UWGNtT<2NW^u!XpLJtu1)O6D#n#3V!0gKfEZ z`M%w#rd( zsUL8K0WnS!JE%ZPQ{{IJzosdQWJ4)Q>W^1Nk$L;vfhA2R#ZKgWHCV?c92TGh8JH(r z!6-migq6IPgd=Nah&mlE_6Clk!-6sCQO}39f`OkNqS$ETVrU00D?>VWlLwKJ>PXCKb3v5rKE7&5oQV3J}WV*&b6=J71P)`fH z>V`|7B2Q|rbL5k6vjHBaxW8$RqqbjOLfdp$bZhAg|9%*LxG`N83#c8z%;2#&VON~`h-Ita|OrZwsmWuA>Am|$f zFmYnooCG+t4UO1ugevq-Yaa?RE*T(cPs?}GyJxN~5ywdgR=R-G5wa_+3&(2w2Z9wXHLH@BIm=NEi{9O#VFvLvfeGyn5HrbJUP1*6g(waf~h+OEX<k3DDxBILq2Z)M_z{@NE_SM3TJ6h6E;?&1=ooIK z6+bCHBjKc6KjGocM+(nv$+r2>C;F71s8bvl_?&MN9k=<)p&PkO3+uaEd<7kBg?V-O zSZ$Gl%z$)~M5nS0Hj6( ze8fpZTScHXAn_X#Lpgs_Pa={Efg3UDUK!q~@pHF$7bbOM2wOi%(hY0^ zJvpCC9ofACyfX-mIyo|;BW+H%ur{!f_a^I-l^I&DDFC9Bg)NFwe{;mjCRMfW&vP;n0Q*@ zji98OHBZ85;R5+C37vyiz;_sTmGpvNF5G^d&LblwFECgV-@u}UVx)-m3c|PL!7){t z7Atk57K~ex-*T`gj;X34b6A?aeG0q)H$W|-^76h$)2Um8cSvoekoo&uj#NsjC3ZJ@+&jza1W1e>*lV-TF z<`W>?EQJD0kaOjN0@R(T2$K+QD9R$cjKG3W15@OMSlF&3OJB6z(RMJRk&RC(zeeWW z18Tl@jkbM}$GW(vL?>-Cvx&e@L*`|X&k`RFy=*OG8}3mE63u*~gZw}Ih;ek$;r;M^ zJ7s5|JPK}&3K9Mbd;R|P^tUWOeS!;Y1fdoW-dC{^`r2>o6ldUI-Y(}s)qQ)mt#izd zxq_+}F_=}oVGli?6{eKJP38<8vNwfcLKdR8pP*um`pB)1p*mY?V?QCEPwOHJIN)HU)e6K4$u50$1F z^|-E=8PO*SfY;4{7RU5p;>d>Wc%6h@6Piu0owI`-&~PcdNL6DA+7Sb zSOs|&5g}6-a0J>3=VXEUB4TdTq#PJ&*tonF{yg6ACnmcl4lgJWfRgeYYmHcwq-C7Q z*ZUOob+#B6#v9cnmuCtxTt7?}@#RsLM#TxU(2yD<5t z8#yq~gFk#VoQ`&9!4$_W#gA5U9aZ3b8I@dp8ZoXM-^BraefS$%Bt`9-~ zv}n!Lj`kzR`$p;C!8meRLEfl1ZFvj|Db(m$pT6#CKGR82I$xZyuYbqU5s`S1LzNos zwmK&IL^j_YI>>6ha|D$eXy-22+T`;$c_HoW@(UNsW1)bIGh=z2Rx)0#5G`LivfBvH zH)&DmGH8?zD1`Xl3X2E1b{12hXkAA+C`i%8YZ=30u|K$#rpQXE$~WcAWTL9U?0KtB@xNxzyAhbE zkbO=j9mb)w0_f{de0}rIZ@`TK$>M3J4+%q8d}#L}4QJ<>Vk5COOOemtfEkwe?PVN2 zau{n>J!qY}zG((XaczJ^xPnJv-5jgnv4oP%+T88X&7K4kM&Cqw39zQ;^T%OJ&4>H! zG){uID8c^?xf#NMXBbQ*r&57j`29;M7#u^1_V`qo4qi(Fj{GKbui zsxsiiUM1xe^REwa1eRU{_jnSw{cd^WzG-mZP%9VMh}Kugl}-O`>Sy@pq3ry^tpr|{ zQ^;Bbj;LXHbPoZ!>;fWsf6$A8=vgo}y@5Q>5bFXF>TmO$YjfBp(efRJ=)T2+e|Phb zVEp6#iGW?^GoWPjw{Y45&MfN>qc67j2O0AtFtPsBcMg=p4u}Ou0g4H-G?F?FliSOUV?ELZnSA$<|X-mAb0FbQ=%=i62XWoXsRI?BU-)%6OrtsT^TS$C|=+X|P z*+xA3rR%Io$J~lC8pzQ~v$cior$t7S9;Skq4(FGKR$%4!*3Mv9DbQerB7S!2lM_|z z5PK(kX*IO>@08M0-QE|^$fkg?!{bOB|KWWGPjiF7O3CpFO#2Z7i`epdf94?{#N*R^ zt-6N0_dJG;vPThswE!`q372aDQ7=WIZCYf*)9;_w^Q;*?;IrD{EHM>xlW3+bLh>8x zMtX}YTyFH~@s#gS&?x9N$mcwLP&#G7(}JRs{8u?ur`$I2gt71ZKAof#@XuUaJYi!1 z<_^=9zzBl|cIx_5(B7kSc=C31@gJ<-B-Lt?Od}B((1zsT00;CB^zm+|Zzkd@*5M*@)}@wnNGNU(ECpTZe7yq288_x*!Lc70*y>mvH@Qcf!Y(GRvjs1zYGL4Jn>oBReg!Q;Tmfy`I~(z zYNW)sgF(FuOm0)8!yXA{NjhJx41`90bvoNl zCetp7uMLk|J;U^89X5s8RVsg}=#uS;l(xj@9c^1*+W?(QQLREB*|#w9HuZbL3LoX1!Yu5d(Nw6#;@Zk^{jyyb@%`&L0|tY=>_?3SlNFzp*#=b?f|)Ew z>gIqzcJ)|#q_qH{@kDERVl?orJiUvJ8N;KXOvt@|t$H~+z=5ude#gOMVUvjDGw#T~|QFwxjnvruuP+MSl zr-t7ROZ2{!bbX%2z7lY17+5=Z@vAo=&hrsmsyz+t0fbBT;x@ZxP~10sm;Vzl&Sizu z{$1Sb$A9-}yQHChN_21d{@^EypzL_H!2DH=2nyz2ug~}v?8_97uKX8d86?tAy^Uvsl#w=n-!jU%(O_pC$Iq7 z@0*Pu>_0VsrdP~ALV{!0w@c@@os%9+=u^8uJ216(bQG$w8Tkp#)jGEMXHXOT1b}tL zj0VS@YtM1oF!K5~Zrc;MIOBLzW8bI&sjR9Qy6dAl>G@{f?k9Ty|B1Xl!Ww)63pi}Q zWOiTB(?}?pfB)jpuMa0dQ7~EZpa}FotQVPZ_Wb~aS<0xxvDq5q3*72ZtUPXOj=`W7c&

2XGk6lBoXvwY?h&iHs)pM!9@5M^uXdmX4x2_ z-@9t9ZZ%KA*q2Cun1d4u`u1k>ka?De!)t-BRe7Git?-VAn+zv$WV-!}WcTp22-or1 zwKi-GvexObc#$t)QZ?l_g{gbImQBz{KB3xDj-Px!5$466V!}3o7uiLw&Yb^lUb2S1 z-#VR*gOD5r6aR{s8`^n38?Q#LC9-$OhLYWP4a+?-(PNxIDKkk08jfY&wpCyGo6IFU z-`-=|vMxAh%>EE5<#L|XzoQa*k)_^<*{!csXpKn+wRKsY5PKfYVy(RhwJ#b%=Fpb-^IQ}y9%V-Cb50yH8lQ$IlZgyG#z_SOU3#i`y??hCVRou#Y< z+X_t%^TyM?PpKH;hK9sACQNl>QAA|y2covXd!47YL|mIuqcO5XYikd&8Av2w7H~Sq zx7oJ7$RC4~#^IaS+Vz*{HfKh%@RmN`bl`hYG<3p->1?;CCwk~9$2y-~ZN17BfKRC5fDkgsqZta=J-B+Bg43seu zZBNNox3&mzd1AS7;tPit{v!Hw5Ge<71c^IZ&xh_+G-~XQ0^BoRjBu|J| z9%;JvpW@)>FLwFEj?*T6=*wDIwD|D)}|O< zL~}mK0(h_8gljYC-3ZuZsy1IeMUagWwuf{RBMS({)OuELvH`bJz~lAL0Zusv<{(y7 zDFYpYP2g~U*%%5TD}B=TUYF9G+K|m2>wK$x2`{AQ4$`_+pGtSnU;EkGD zS6q?R67qZ?WVG=YHW728_PO%n_vgC*cW}aLqH2Wy2RO0Xe^0#RCl=vN=ZqeQ4Sk${ z=i_{F$4UL7!AUS<|xBSrumVMC`<>h@tpwT@Q8zpuLQ5JutUAv z)fcIFEWxC4u2)gz^EEA=A-TndF5AE`dRZ)>ocV4AeT|3r(lQ{khSeUVqp&()N8q-K@3rvlOJxcZy3yIEEk z-Q||Yk9j;C=lt{tIQHJv9F8V@yOT}}!{lfF!|Ccd(h7%+w>q)#6PzC0J1M|Wg!t*} z!~Omhx?rNP+<^sa3{}Y zVca2Ki+wCYTCh}_?%e{a`3U_@jc8M%yoi-BLtNYiop#fAaV;f(on|_h;c8Nj=1CD6 zVVn8hM#zm~O@mR;nDh?e#A7Z|`5JN^(uJ^$piHZhp`>q@a18dac6LD=Xe*%qJJEtY zN`ZIn-L0Q#(VUblVDZG;HHf{BC>I@TR7t*{L6tn8Nl<~q6iOpGD2?8~&5Sw*+E@Kz zAVEA66;Q-H3}{|_A_2|p%A@CgoCAUgJ2L;U8t@OVzI|s{YBxe*-g)+o@!#KEngXD) z@!0pWv_>ub2*8bqOuTf-D}4%xpWBszBwjZ;Jk1K69$-wJhYC7&v8X7G4IuR-iQ)a0Q-%v0jm0s*+-xUH$O4v1FDFzxV@L zPfZfZ9sfxC>>2PM0kyF?p>Bfp4|szrJqP%&D+p!YLCn%q8Lskc5T*2JaeTFTq(7gq zi`8LfMkKu&dJ6|^r*ec`=wpaeS|wR%e+kjRK%?O@y=D3fbV{XxoTW@#_*P^ntam@M zSMbkU3$91vCEC5zD7t9$jcN!5fd+tA7pC;sC%`e>ZGyitkbIZEd$WE~z{%a|o>0la zAM>!*4RSW@=HvjvxDOl+hY2Z)@6iJKp=wb|5!K&SbBZ!z=5@ZG(dW#r{lM$BgF)nE z7VP7Tfx`c@g9}qR!4N!_+>%E){BNz4$u9K0KBqxdq}dF!@Dt0tT2PCKSL(}lGXib? z>Cyqwav@c}THes@I4VkV0@?ow;6gnF7u?o!AI=X9Vp23cJa0zH`_a1 zO`UXUdZ^KD_?dag<*h*;G6G76d=Wwr@fu!p(T>M`@yA?1c(acbtbGaT5OvjH5MGGv zG4DYyY_1cND-{a(R|}g7HPfy1+q->6A%ts~Pcf&~&;O6M-#4779QhPx7gXm8*rVKv1WOMB@x^_^n^$1${}Lf_qhD@>?zFhaV|_b!HPydp z%~WKB{g~eV_r0F>jYC}hTDm61Q$VsGGucBkgG{K~5x$K8Cw!b?hNfjtnjgSp+$g6JY1B=IZg>X1cQ&?Y4y-e-xfH! z3|?dSsytWnsTJ^&y_)5l<5@(6S_br~>*vL_1T z{2*}(L1I?)U4igjb3x<0A%-do! z3T9iP^vM@Fz#FduqrkE&1>x``8a`+oVm2noYPepy_n^2Q+$>z-ZOvI;G;BxLyVZi>w$nqpp%dVaa2M;{=n=u>F`n*ZqBU}-1+p!Tm#E+Swls@b-mNRz3hMQ zS}4Sxb}xz?}H+K7)PlUqbmt65lOku!2U7CeW!;x>3 z;rcuvk{{q7+4uhBEz(>%^HAk#4dGEU9Zyn&43 zYTNGGF5o)Ey-b$N&-yCHz(EKNQwQP|TguTadSqY4Eb+917%MQlg*w4HvOjuPTRTW0 zP;OtOy@Wzc=id6Vi9>-wz<1Lq+Yd$mT#CKNs|x><0F+IA6~ZZS5>Cu&n)11^q*CQu z%pJLdC^Md$(_=LzcKQ!>pO8Hj8M|d))Mgr-mI)aq#A0~%9!7pQ?l6t5+BhZTh@ZH8 z0rvRDhE{fU;5z!nVdNuh*ElL^K~_ZDpgt&#UoeGS#u^-U>UbghS^Upe0E%5?@OPK$ zfwvN8rNDE!2QtBDt2R2Ra%OVsTrj#QZ9QmFdGwXghc?tM*JaQ#l!FAAKznO+^2Tc` zl9JTDS4D;JSeinyHcX5ATcQl_?Qukqbb9Q`ZUY|uf;c<%~#v$!&!db zIx~)Q*F*#?gbzf}F-Hi8H@yq}fX-JVygqn<#1i%z6=yzhHviq-*zr|y?5&^S zyDZH@8Olzx-$PqJwZT(R@kJ{OM*#v6VjqPyBKr~~gz<+rQD0qNX7>WXEz!9|qe4}? z#gfpr&13_up*2yF%Dr&1W~`T0=!(Zy55OcCXDDu-G7Ei#=N;zIs-Qxr?k2|RHORMpQX;*1{F0;^n~ zltS$Rk61QCa*yUSzGmjN0DB$ZWsAGJ`&4%en`E5^zWE^N35-%B4?ukmt@B!3P0kiA z6}~Q^51a)iEwZ9Jl)+!|08})JsvO$YW5v~9u=9RdbWD@Blj%Fg@eOl`mEqt3OR`gF zobWZ$6|%qXR{mgbkW3#o*OMS-h%Lv)aB3J(v5qCIp8DTgL%^I2+ zU{?w!;AS_oRQbA71z+Rvq{kTCeu!38=84s^AXIYKJq1o$J7B#_K5}hoUtJaK!+2m^ zobC-W=)gjII93)m7&azT3&aPkCTyAmBUAI)h$dvo`!-L@u>Z_(JK{VRxhwXF-rv67 zQGXMcOqL7N@-qZH^kicahEl&>P8ko=`Z0HpGX6<*43f{Hp|A2y&*vNWAG$`z2LKj zi@m1nYKTy==LeyJ!nB2JMchNN!mY1;{%UT1@{xs)f{o_IT0aPqQg8~TQ-=ieq_~?P z+f_%xOCEykB$@~T>VBkk8}@5#KC%1mDn8;@o;ro<5Hz*t`*>wD&qzf~?tU<7(+xB7 zOYpdlMvIdQ94jm0?J*wvM5TzgweLWsHIo=wdvELu;TjB^gb&u6XOiD$xCjq~du-y* z)WS$sM32YlYmQYA;_u+avONQZNn36lk~^Z)UM(nZY}M0hFR-IKl#C)TBh07PWtiD% zVx6VHzUOAIn3yS^Pfl1;H_^8KA$S+O1Znwoc)Jqswh$K(xqbn7nRg@9+fh8yiS6aj zin5Y<+p}$+hJbO)EOg0P9B>sfyNzamUpDTg{%Lud&%-8=it9zj5(5W06R(6g>(rwlZqc9LHA!1dSgDp+4igPN&#gV%BasCqA^asJN+s~NO2RQ)ZEjeaS6|AiTqY~uQc>uaoS~vyUzZ) zEh6sRzI~G@8CvVLQMxpRViM2-4CxO^PL+Iz+rX*7v~X)nz+W%f1F7R%G-4GbjGJ)n zR2U&u7hME3Yu)6X*mIyyOC~<3RsJ#a5BzQBe>^4yT50n`4DopBjBrq9#VnPBgSOB? zw7|{+r_;S>>$95z^6QVY>}7<5hRk#)%T?zZp7{5SJPScs|YlB(^MF|Y=FBIBYheGJo(N5&ey{iVu8J-(VqW@w~2;tyS2oz-{ z{ZjSK0~-JeTZi+?+V~$>LRtZODo*!rpZt}B`4er8IR?MCsL%X?L5Fj8sS7wRRHqA^ z2Fs+7ai~MDd2kyj?M!iLgyDY8c9HbxF-{s-gnZlsh<;WmX*bPsD)C#|H}HH3rotWE zgweQb^RV%oZJ>hqHsLe|e~3GiP+z9&zw%t10cQ|R=ML^X4bCR6P%E!JxB&C2)}uD( z9RQ`!mw$p%j#6OKx{peS-q#5Np$fpL`<2Xx0MF}6=lz-o$Ste7b~O;ZR? zpwgOG!SyDhH`g!Nl-QQCJN^ljF%B7fQT=j=N!#zFn%?wZ=P8*JJ}{$WO?wB}4DfuZ zF(CH+8jD84TX)Mpe@(#3zfN{jwM+@8TY|35x99@QE)HmfqKKXLMCnQ4T zf`^U;m_i_4d_G*$3m^8nmr*k9wSopImNHl2D`^EbHxV*>W+BYja|mS2g@8hK09n}$ ze3B*nyPyXh{Dd;P-hmqF$**>|IT&Q&DW%YGG@km!agROT7#Sy*1*IOccrhsaIRq!N zN#ZJbS-vB!5z47R@%AVP5zO1M22!Md{NU6{rhyUr8E822-v>;-dRrq)IXm%B~@i~X(^P@ET- zDwpgmXl;II=*-?R@Qb2~jX)GtBsoS*QjBaB>vK5@5V0Kb>eZOL z6S6J~n4~J5SMc%$vBeW11*CI_(XNzHbZ&aAW*PYE4PRU@zDMVZk<8Z2$1i0%%)lRW z&sDr8c41d5=xGL=4l{n?KG)f8#6|!{M1pUkB_odmd=yrvk@sEHcFBs2&O3%TEhAq7 zuN;)i+wNJH&T{feTZ4C|U|6HZj`UU=ueV30VDWUoAaa02@+b=%L^%(@U$IF@K-nY^ zhr5(lerb)r@VkvNt3|W%+4!zyN`hD|Dbtn@cwI~rR zT@KZ4tvL^%R<1rL*uJTZtkw4GPsvOX`g0I<_!@d61>)50EZ~Az$;!9BsTHv-=fEO@ zHT(^~kqc-#z8;&|zqSUUQ({eo)_Lf5T>!tCbS56gNU)qJ0wpIG?n<-Ur$3rS(wiM%&2<}t^BDp8jC1YBv1F*$py#JR&p!^3#W00s`bvk@x%Uo; zpOU|+9oSLBY8(&dn<(G7!Cd!gWUWAO!z_@uG2P&aQ=gImLNGVV-s411W%6f|PHN8PMIJg1v>SQG0s1zi4ixGc9N zj}58!1L9*`qNi8wD%&#w-yBEk%lRPAL7y^FJbc&)SCPI5Uja*DdJ%BFPsQu31VN(^ zmch0gw{6lwM)-EhSF^uczdOjR)VEik;|&x9zPrzYXyPGY3$2JKFu}yIwyG2YdvZX{ zQ}O!Z-bJARfROwMoj@O8u~A)id_EU7W~ZG!MW^HOKh{AR}_e;8J&QL=n9>iI9ChIt-6JU-*Gl^j9|UH zY>|Pr5YG+~dHC<{&Y(|GW*yw*Sr2v6t$FsA%Y2937}p)aPpo2RohWzYv0?b+8S+Ls zHKUHx=93(#ninjZKPT>mReI+)CRmut3~Sidl&^w==4CIw;s1P=!Skq)+dPnmV&@G| ze5sX!d&)_9G0_{^>%q8FCId!&i9+R}$$W-&1}+U$ysKFmFtRzeFONk%IdOP5Aj3IW z#ri<2#|rJ`qbu~@9R@}U^D7iiWlH_s>oo!vfU=(7#Z)lWqAqqP=sfa@5LN*s0Y2`k zwlp~Kteo|FzOj{oDVcQ1NzkakKf3}hDIF=6p&0yQCBl%%CS(GGyJU=DU+X2Uq-2Tl zvCD)zS2}w=DIo(O9~l^spX^IK1cY_LH{k<235}o3MWRfg7<$TR(k}C~z;dNqPMRGIjRdwAm?T1D!7+(2u|bpS+L;>%hH@@N$4bj5^6;S!wjg-r z8lXo5U&OWocpQd}aXsb=vFrvax6q@*ajpv_?;QaoI(6GD;PzY@v9?<~Xej3yIZ7ZT zwuYr27S|_A69=etUM7@j%NlpFck4B8WlwIn3xo6+e}>DuuI%51WKJw)|js^#0(Vw3fqAv z4m)APfqPxB@hOk-<)Nq+iSclH@8;6ldc4K}n0J=G83aLB7BKh3Kg6U^8Jg4XwJ54XRsPGWxTqI zgMxW7!@4?3!VC_=o!+2XxsBJtPLEyYH2Tur{9$m20jxewZT;{N4zNed&d4fNY%yb5 z-}k*@`fEaFgschV@2x8(<@o{9UWkkkprkOqVMk~w(r_#n!?my6{Z%o3Dg=KC&Owe~ zwXMjQ_S@vOgJ2N}Nn8aGy))aE42biC+k0_^#_aQv(v3MlxAdE!OokF~P!}^#t0bOz zAP0hdX$yBkV`R?OmwI3*lW)R#2YzBOtS8Y|mz#3_y0CZOJFs#3#!i6CEvz`QSax>l z>E+sE`xX~(ewqzhVjO-HAyK#$ei7B2K7YeV%%6cA+qb!#JbUxErtLnk6lG3SGAZBl z0KW0oeI=1|eWHeq2cle)X>CwiM5Z1)w4c3xr-a$JM?Bi49>zJSr1d>q8(?$&2x{JV3pdDgll00UmyOID>eyy(`lm%X|(yzHu z1H~MzV&*e3TN1ydn5X{N=c2;6JLv)(ZPvj-P!o0az>G0IHpO$HBzc3*<{!F4At8p# zqVgh~WDQ5nY?YZQi6-;10JNZ7L8oIf$V@}=1yRPA+yaDFk2EoTk`ozxz* zsA|3&MKT6}^J@o|Q%>u*4r{{Oe}d{b&p-L>M`v&V zUf4VjWYs&0u#mtR?^<5X6&qTi#1Dbk4CWO`oO|X6mxq)CvX9V^(mnL-E7dgs(9iG3 znKJ1C^1KynG;KrUKWvAFI{JRfvRSSnBR=K!)L+AU6(ywNiJkgzzR%)N|EzCOC5r*R ze`3Zj9zC$$*nfoedi#Mf>Vmo#?7kVRk}LF1=r~+q-th<_X=rd8u*vIw88p5iH#DWc z6P<1ZJc2t{9$5nhYcq^DPWGOl3})*6-E`~1yDFk4R^-Ej&-d*@T?Imh^nhI-FJa>b z-CI8Bfy`mla$fLvj`5P+qS&L(6NpKU1mTMZ7nkRVvcJs{Z>`F3D!SVH8U~S{f`&eT zVABO8F%H>lGF)%Ye*f9_NwS(C4^CuP20n?W75%z7mu4e5P%B>R`z%WX_=D7eCZ|`ovF| z;fK-zbb*K?pv)!7apq2&!sezT$O7vCV9X5)g@<4W*8#%@TPP)R8>$+_pS;kexxtij z*^IpypQ#9HZuF@mBPQ23cMJ=`m8l(s1}-3wbyww7x`g_adB1ceW{OKA96HV7k3TY8 zR}Lye9^B$bMdUf+2E+iGRAF2f@{i5;kGk9e*5HoSx0a34%?q2`$P_4@kJ3e#yKnqT z)8hlIl&wrQR?DHb3=Hx#X6T6PW{dj6hRSnql3-)*ghb7CnTIiI5ZZpc+GL(+V zXe;(|UQ%Su1vc(t2{PuZ`UL#Z(QM=lmO)3uWJkBFkc2qexA{9X?!x|VU}R&+gD`|? zB>QXyZukK03{W^I;E(G4#_(XqUK^`r8EX;d*)}EQWd?{WKz$%Srum-s1p9s&_fHxI z=O%o=gQ%z#dNU{RmdZgfNy-O-z}{!MNnqF!m~H$prWqbKG1(7L&07zr9C%T2NXYM7Yc7;i&-~LtRV4!;)5L*3@x4vHkh>LEcZd~7 zwu?-lTLLsRT<}^yg^nrTQh;&-s(Jwa=nne68H-!k zXw6SXD@=rK1ag}8aabX*;j}=u{I}Le9BRD(1;%PvjUqSj>~JngxwDzjxWi3e5gD#D zgK}$`I|Mb(5AINyiZI)&#FUJZ;-o(<_o+xWb^fIJd&5)du^}gKYDMKG#k&14g%@&x zT^7)nQuT&2cyMy6F*QK{BRCv<5Y3xJ(iZ<{z-IE8#SJlk$gkEFAU-n0B^? zI9QtTFaFb34Hej0$6yO85T1Nflzd zREa^lwEEfNpC0;ls5YQu{9dKqf=Tc z7oSQ(_1Ya|9bQelCTTaJ@TBux!ZIkl5Vo#|(7i83+VN_+?MP?QWy!~kH)Vkk>^Tc%Fij z4bc@O3R7Tn*bY;zfKe1&i;!PLdk8<#wE>0>ewhHyp5$`edl(g*gUe*3J6jklJ{b$s zbaH!>sK4R=Dg=O=Urbh<&Y(ZI- zt`M#}1xU^;&*W``)ReDseO{_QjX?dvtFpw~|3sQQm*$=><%35aRz%X=I^7d+w6ngk zhiNT&||UR>CqJu?wgKxo}S%pFz+$ z^%yA#5Y&l$ONNoW8(cJBKYq}P)Y{=teRjC%pDBUrbG-R2I#&;K0HA1EeWWG%_m!;k zqdt`8YBJxc9)*nqs7O&gei7gR$7+s_%HYX-vGg%7rCwS=qHH_253i)}dQ znN6NO!E3nvZG&_mC|gkP$U);PDr(Z=Y6FLwhJG33A*Gb@{{phf6VbJoKtWX{^B!-E z7<9<5As-c7tKPwm>kLMNkAQ07hcm7JCS}^61LcTcc(gr$L0uM8@?3H(u^KyA#rl7@ zWYIMv4RI>^6^w_DgRSYynO)kyE21u4TA+11e;%1uqlPTI2^28N&73vy4+L_(>jVehItK}@8baDFbbGwPC;~aD}u4Us29D0+i0KDj;BYq z$F86u{LOb#>7wJ|)!TTzz)qlmJEVO0IYLy75gzW zz}6a8Pr~*vXWb(mRy{X|OndFF%2l@)x_;?%1)rC>`He~uDNulSL&8vQZum!2LL;9U zW}_jhVAjPzJ+neQ{K}ucA1upz^*&JV&wU;2$<(!9|6d}PgFYg1A?qds5wN=dpt;$I z=sCa|w^r{czIpS-jjCFlTgv@VfZrR9PsrTUT5#KMVl3p%a#lFh{)aOQLeRIF+7@wv zgH)j6PySEGKbgTpX~`lU8+f&5I{$;6yCUqoff>W&)cPB2&R4;l4(>TJjVqxd(NN*@ z==OwmhvU-&V3P~qch90Le7Dt;9W=)m04)j7y#b~wnk}h zy_oCC8~tGs`F~>dt#7+AgtL%ps@pd{g;5}mjcI69gf8p|(@!xda7fcD18sCE$*hou(iP33ca(6_x`Hi7+Y_pf@_?CPx)xQ!(+aF=DHvD zD@9=}@31;}l2-CwCnNLyh&+VPdjzC@2UOsSoR3h^8XPZt-NIGx<4m1guI{R`GRwF0-^)r_vb)#{q?@VV`R?$Lx8hVjaTuCqkF$JZj;tFh*iKg zaqVp`AL7xbc3C2ar2dhhjd!5^oeAgCI$lfILf3^1$}^e*^wAFa`E&GizL} zSzTG^vk;Q)1WsMpt!;J%$eL8au7xo%{2zN8-bLBeEo&)&wLZeyRY}^dkI=^`3qJv( z88CE|cQ^UMf&Ju_nqQT3n0|H0_6S$%v+Zk|l|(Bi=5y0WGT6wXOtNl#wPiB1VV06mtn#&%Hq&xU31} zqncmODhVP3trP~#%)!i8OY;ND*7`C)Fw@}6I3{e^U>?e(+w7Ih8-5}E2d&G96qzb5 z!lF&~>g&{OJl1`4U zNW=vVewM^jDY?!SzW2xjnm)}w6jIt?Sfh`>R3e@FRWhCEDJOR`c6x;kkAE9k2i=SZeP8fJgMDrjY53zJML$$jQy|oT8GQZXX zIPm$w%a@M<=6G&s@B_81jl9sDvg{c21J(KQ_n1xaYVfD}KDNWtuD|%7>Ai&CIjx> zmD`yMG5o}PwnT!0rao^rvj=9pA{#uPz^5%)iE+DwSAwYdr-5+3w=!+^Y!VH+ZN}B= z@>|Q-V=dB~AC_F*qE6x?!-?xF;ly>FerS1s=lGl@ki5$JCz-475+ZY{5%hJsnzhIC zu7nw;l$*y9`Z=BmX7OkEvs@?7WsoHtR9~}D#;5G1nh0k@gewwRi;(XDBnJ7UZ&9Tc zMQZCeQ!qwyqxpbMYkj^}UFKLepHSK$&!;aO#3dpRO8((xvbSRuYvZqF{Ne)e zjCMZV5nxYe;frBI4cm6eGsvr2H^s|JS@mQu=QY&On8-8e_?s3Bw1oU#^G_g%#vtvI z8yH)Vw`yKpB_&2vH)yp2$&+@^YcueP_>bfX!P%#QQ*oAfPmm!F`G9`ijl9whsQe@; zp%(dsAhU?lz{B~`gp+Uo0E{6&4H>oU%+AVgG{JkYAMdG-LekM31OzKywN!@d00*fO z{7(@S@T4Xx_pCkK_!48Q15V8030i`xhnnNINDB~z4gNo_z=)SQK7}6FU$0F~Ze|G&_*Tp4T=0D~yKo@`czJ!e{f+rR`}N(KUi^cu zB_s*|8F*TS8OAABH5}{j;D4Cws|2%zox63rIb~I$Hs{sf@AW4!4{n&_@y{Q!2iYan z&&tGrv`Qq~cX{h`VgZ2t{AX#Zu;A~@)? zZsDT6r~Z`R4VuL3@yox7qGliG&7GvBEE~WiTo`W2PDSt|krw%Xw@$^e9j75K7Feea zJKQ$_1T#G`8`hQ)Fv9*Y0YT^0;b)AWa0XZI6*#VtNV@X7^7rrqDC-)wj<#bILyN5iKazuC5`lf-Il7Z=oyb_H8fU}(-5~KhoijspHpmjaU z1?`#FU~^UWORYV(_`n1)s6>^$Cq;YRv29xzgJGb`<^K)Z+iBW~MzIF~TdPKjwe5li zWGxOa*r8apPz(u3*{NDT`q-Fc*edHd2G{*oLqxhN(j_1$4IA`y%l~veK#L~rJCo3`d4TgR7PO##{bi4^ zHUBG4io9G+9PBtmGDG0)zsY1b83$3M2Zo4TRv{;Dx%u|{O1Fg!7Rv2dpLY-s;`Y-J z#P|M8Out5NCji?-&yBM;-V8#w>(Y=QaZa@zcF{clk&;P$Bo~9kGY9cCZbg0U29cx< z8l1}}sjRkU*?ddr19xh`4~Bn!qn4O&4V-ty!uq9-WVISffj=bxSzWXr@2s$7h%oPCg3>Zk$mh_Cg|Mo`xH+zgJH@O}f?-(n9 zimhO{Jq7n^0nXQ1Kpydid?`O0jF;V9w-=|gN^ye!aoS_%_b85zMwH7xbB#+3JW`S1 zb~OZV{VA5>i#YxWxKalIZ#%z8&}l(=a_%ibkKTLd=QqkXpfq)VFhX^59wHzU5HwNn zzXw?`z=N!5gIjTi{xv+h2Mi6yjHoYSk%?+2jI1q!D4+x+=RMQAF7psPxMvqPjAHw1 zWm}^`%yED7S}V&OMpTyeJ?HWHxZ zy?Xhx{6tK8r3m-8dr$tp((!<2-_jLr_yP()q8j-Q@@uo&f-(xdn{n8p0>V~`s1)G^ z3Ki?8rH-nt83)jBnYHE<4&P#eu4W21Q?3sav+~zV$9r6AAV{Ka)lUXn5p>rHMcV3P zhJoyBzqQ&$w}r9rTh=4van1gpQ=wd#S7!6x2QSm-(8t9d4=~)39{&x22ykN^BTq(^ z5{^TAcq4(f01wd>maCU93Pt1mBJVSH97Ru9_Vcb>HbzY_dLI1d2YW4@Z3W>cd+qG# z{|^Nf){=B>QVzLu$J6aokrC{`i_Qah`p1dQBLod>=12HKYl?VZnLiOLY_0gd0EkL5 zxBuvcm78+FJ?NzX9R@+kW07EJ7=7G6TVbM>AJHX!ef!2zR6O{M0R?i~_BQAEd9d8@ zst!J^#h7nh65S}L=r|W^zgd>L)w>zQ@MU&OO&aSp;Aa?9#VD) z88$LR$e1~q#|#^p+0v*GDQdH29xG$!=49ArGL=RHL1@cU|9ieSe%T zo$PnN@AE#xTKBr|dtIqmcT9E%t|cteZQS z2qE`kwc_pE8Xh~HZBkx+jXC`OVuSoP5XH^$#{c1%`o3L*ty8?1#p}vEZ+9isy5`54 zQ-c6exjy&WcFXpsSlc@pInKdnfy7@ent8eFYX8f)_zuRSN5jRP?yE!KE>3d{z<1xChS05HO(I7I2&3g#FIv!X4&-35Q2`b3FUlsj+akF2{bc3VbVUK))c z-(gDHef2wmOU`dPRrPNCA%1b0D+fzKsm{7@6`m4JXg+b*LXGL{3pkY_d6xT@y$T?E&G&`eP7q(i~0!&YmiG^ z$ICk(Ui|{gPa&;`02unE1gF!^Jz?Q!zNO){;i`9?#yf2guZak9H2=WMKfR;51vAU@ zcm^`}pzqt-e}WZRzhtk4EvO5P`wqYMkLGB9m13`G&?x29oH}=4F(LzVTG1&%=34(t z`nN{{A2`wRlnd!VTg+c@R?+>Sv4(V#}J(CB?V=Obh}E8vRy>Q&$QS7y)~w#npJ z_ulo;fnjNb}%9j~llOxcN+QN|bl~RW3RN!xIRbtRq zd1whbr z1OuIKb1i`9FGZ7}sq5J_x74Rh&b7fmy>)pE7Lvp_KMRfEX-6)#(N(MwWsv?H!x?|B zhyr#Q|0T z%{KybJDoeT0xs!%+@&0yVgJyJpG#lj|4mip=zIPs|93We=v5`E7{4`u9dPb=Fz5fI zA(Nd@T$Ld92`G9tyxkXh)#eX!cjVGpo!bF{kD1lTFMVDiJ`17jW10i6LHp^-dAs1; zzF)E4BE|)t2b-+Y*j$l%4PqU~gqqCfmvwjr_#A{V+Lb*}{6}4T<1g!cex6+H2*zUS z^(zqT`Fd#}!#+!<_>A`!#w2D)TmJA!1s~R3?76|s2Vc%tov6DBznJ>-mf%nAy%m6C zD=2m}9O4!Iq2%U0I}VN0obI$XF75+Ru>U1Ts0CSSYXb+uof4pe?sl7fJQ65Ie$Iyu ztcE%fEIh;#1+7zCC29W-eFVK>sRUR(0<%=)2lrP#UaX%Ib;$T?=64n%FGgR|LP}bD zJ%?6*=`E5~K}~*cQZ{TQfb$WS^j&}_oY;TaMS-%@L}@EIw<=q4UHyY(w(3uk(kp4u zUJ2csk?!BC=oCV?j*NaBf^5VwL*%<|c!*~1sq3k{%0kDr%t`?9R@jjt@F_rZTYNa* zkaq5SP+5EoyFYq@rZEl<@=c zDo$Ug9ClCCXG2`q{DeC+Zw*axbW86Vfq<+>_><|0584&hB$iKu4XCjs^J@2UR2_3C zX3IvPYPjH9z(JYlY#Y~Q%3rZ196I*L*h|6KKQBMM^WNIcW@xSsYKxeG{!KtSy1ZQ^ zD1*wU43EWPs&V`eS`Pzqx?U%WKmQxs`n3A#k|T2_X^Q4x5@4e7;kWz>b4hpN&o&wn z+7RzL94n%p{8ud%!w!3oYHg_zyL%&khoXLz{;8$fcV)Ir&eB9vp&qtUS9c-dVQOjXeRp&zBsp)b5(^$RTK5g-4q9B z+4OVHX(YzV7xQY-XS($rOMAYJMfg&}UBcecw~K>w&GNk#m|nNHNk2m!twz30DfRlx zj0BJ*TbdVxNLZ?MG|WoyM55E6Bs~US za|cgh#XVk0GAr>M3nyZhW8uqwS#QUao_w`6yGTV%$D>z6EgE266QbL+72OWpQ$#Ek z)^Rg<#@DY*Qa|0aODdu2wu7ci;%N{Xvi9(Lo1U=z0d|2UsD4bVhU~UyCWi)={O#zZ z&b&Dy2g-rMpt;G}?@i(Zz{g%KSwkZDx^87TNIG7pw;!m2$Qo8E;QL4YnKm~a+S5Qo z^B|EN`uw=b>^|(Z* zs3Hfl{{$}Jn6|RJv1Rv$mSvC(Ro(8(Ti|uoPgF6T0)ALF2sj$lVz}Lb;8_9!pNC1& z3#Wg<1S|o5Za--HP61cs_7Ft!NH*qQ8MdQ&{*&Fp;Xn>#i)n@$0s{(A0Ru1qO=^ens_ZRYSLPNL0+9;^K7ZZT)k!2dwj?I=e#Yh0c?|@(yb19>=_dt_z zdfrwGF%*k<8-*CF!*9e-F3!Xwf+(AcmX8)mwJ=&Z2ZH1Uk3?<0Pgs_B#~7 z{2xz4qnB|=KRw@l+N#cJqpR>UV+eYYtX6oDng&k-fA^|36Rk}m%$DGXiwIt)TRgkw z^ohHj%T6l?&~JMU6C-1eFPbUs(AbHz z*Fg6iGb66_FujE8`3(kHb~n_JRM@zHe9ee1GwCM7GZtC`>aKuviwM}M8a`-6PkSkO zC?_dRxZmeQ31ivzbO(VvZm`&?T`(pED3=u-TK*NHj@oOr+a zz*nmC@h9Hzplpw@ah;{6A;^ql#3E&(Rk^f?Clu&bEpLEfa2>Zvc~1ffHO4@MDUWjE zUrx68 z8G2@$-cFv$`D6gH<7ZR$Ky4X&@&pVfD`O3so(d~j}F0tt92y?!B zznp%_VRmk{3Tq6nkx92)M;YQKlp3_MBNNNY#=Zsl=){~cKE_S@G=gY z?GOtkgKoqL@~njo{;NYn-aU4l+8cqYp*VO~Az7ay(<4d9$^^CZ@z;!+l<56lW=~5< z7R%>oL3-5Nd$h1r5#w~sxEKC>3Nl27D@?Y-i#;;d;J zbqDH_S|?lDqDc)?Mq1s%Owp3*1{nD=-E;?BPtJ*b!67YYji~Z@zQKcvZ^gOn)@`}p zRa}vFy+BhIn>`uV7_HN?U|6eyk^MkRFuPj@gj7Cd8`{|9_Ibz~FAOBQ?N;AF*l7-C zc%DI#Ks>KAtbbmm`w?s3LXI9UIl20|2mSd$F4i3w(&48Q13Q!HlRb%E@K70iN^Kme zSBaRyJ?uI0bh7KaEe*F(p5L18es8vTRm3sM)58#G(lg`upMQ*r+^doUE?N(hywTfR zVcYD&VbPMTZLgN?VBr$b4R%`9O9zcgzoJag4XildB}Fi_C@aQfrtzH6s&J_^Aml&# z4n$#}-j0-bGc%J#%h9*Ve7Os*t;eEl&3cS%T%a5^lmF^nvSC1h@$kzV%~?_@tH~S9<+$jQinnXgr~#qJAU6TnUiL|_f(#576GqL_ zm}QKql2!-FjKwt6tm7fHF!ZQzlkxfdFf-nsJtS4gAPXth+24doc9aw-Tq#p`tRZ5I zgOKG(XY=WnUkI&xx@6k(y}&97myR^>?OnLOxMsVl$9eI<$kthe@7B9Of zwj+j^SW~{djM45E9ivD2rgwzx#VqqvUB4cS$}lrVgrZWHxA z^9mAe$xaco%Tlsr!&E03d$E9gmM@mZshKRe7cTc47}ZHu-3J-$B^TrIRMc-6VVOzu zk*7mzeokDbA%u=?9gU=%y!UBOewTW^q&~40IT5F5U>bI1LvbgD@ujj&a%vv8h{m+R zQjV54btt#(tFrKP*v}HFumV`egDVcqxNSaPJN+mdU9q^*R8olT9t0zZQJ_*LG6D%@7(;O_wCbul6SgDxptP=jZ%r@P?ll;jl#22eZqDK}IClOJ%+b3EBK=PUuGQ>k5-#oaD7c+WUDHfje!`wEl-VM&Y*(N4<()8eA#GeHK039hZt!+LAN`=M@FWOrg6ws40)f zaDpdkIKHifIVeSH4`mR;d*S4;y2Af3rT1}0Z*SAVjTI{Bh;E1ow~i!1^k#ZtGuJrG zFRy&+Bft@zMePI-a1T7et0F&;dco!bmjlGq#lTTz!F@i(MEi3a4FNkTKYEQa1-uxT z@!K5hJ6+bsSVI?{QNE(I^}Fn?>4iXN>G67jNr)p+=i--ytMTNKq&KNQV7@@>DW@0j zpx4@I;1_u|nL&GpKCd&~pw`&_Bo_zOKOLD*32sIrxnm2GPV{&cuN;huBZFBGK^jsSnweaDRQ&rc`uWg4) z+u-e$gq!v7)o$jmt+UGFgbo@^t;GSK_XOQ?`^^PNavTT3W+~Vb?FsH{NOcSpC#l2e zc?-4G2KiTLk0P?a)kx_XFE}G?jo$%Lx*P(TPsM@uZ<_95M^M9p#MIi+y!*yC+c31gJZv5Id#Qo9o&4kf+bQ)x)d}V}k{c61OYZ-A6%N z{Df!_7~?2-Mp-w6wSJt$HBrLMuEzt(!I!6+C>#$ zVfPx8{>~6Zl^2?pyf7lLLO&b_HH~0QkAzL zUi>hc(d)Am5+~Y|gV&e4ghv~F&j4!9p{thkbsL~u4 z{O(*@T@X~%kGJxWo4u^yxp=hV`(xOpATcb+N8Mg~xgp1Z3}Ww&tPu*w!+@=P(H3-%;( zbb&W$#>e54%_<_x{#uGOga=fm>e-!hv-V$8VC8HW{-tD#O@7{!b{0Pfe4H_)yi>S^hb6Hqt+vfLGOW- zUjbg8iSvtsro4EPT_!$=6YJ=?crE$&5KYotr&pkt_vzg|NWXSsT;I+^)_&6%zpr+) zEG9PruhVk3o!eQs#Ie<{sRcYnVo;OZ*U-Vn1)83op5L~>@)NcXUu!9mkDNf3xP9CQ z8VL9KLgSu9R_)c%VURAvO@PVH)48u*x$(Z>{=c+(5_yYFfxe>BzFIO;@7?o# zB9_1gHH@?E#D&I=vH&jQh)Nl((7lg)UEG8w2GrBpd%SQs$96!pl zu`%O5pY`;XqhS_2xlVB-;isCTnqyrM&*Gc_xw-D3|8EQj@~e5#qUEeI$}*j|gemw^ z{$mBP1UyJRVss|_vmWWcI}Hx8LvQY&6nxPi+)j}QrW}BO|AN^OB>zGX(o!Evm#Ou| zgm!V*)j`(p2P}qukTDEdr3l9jantgX3j-k-q zoyu$LU@C@cPfpkZKACb3>4~oHm(KMNPo@|Lr8{rP#5bb25PIO+p>qy4>Q?TM=@S*| z$%#x|tpK~*1H1h`a;==WVO-{7gjx~bZqKd#vNuwD!n_yoUuhM?m&l*;S!+|(Ml{^~ zaO6kexABm9$)eUJF~;i*6EajSe;r4xwaQ|Y%eSY`_?Uc+)kJd+kwjOm_`aFB|nhBWsii0c;gLPziLqpKy zq5Z{-Cx!d-bfcqx^_*j&<7GX^5-br-IrRh)8pSy$24nrW5)G1GI5m=`fW)6@*aTaS z(?%{_EEn`j;Dg@Sr1{8jVhL3k_HMH3pGiN&LuaYa5u-OzzJtLU&DM}Rnr)RJu;>H! zf!kJAXHDYMTJ%NTX|YwhqAsc`V-$w|>)&j_Oqv5Q-7HuRvyHvK9B)cgM)b z&kzgPeCA&}CBwtN!pR_?zU#5J-dleWcGcD4d}Qy?sC``sS|l5Y6vq3vWr>Go8`e!o zNS1iv~f?l@!1UNL_0x&jTy95lx`vE<51Z-Q& zX%YHSy#}cDswEPBKk`zoHs9mnN>@8c7vxbxS3eZd!wTOHI(KswGK&L>8=;`Qk( zb{>Q>TcAETgDSY7dKnQyVYiJ55XX~N9tggU-p^1f6eR+<(8Ca|rnT^jYMnT({w8I5 zY;D(w8D&^A#9^V1rr-Nq1i5KP?qa+EuI zwIvO;7M{o`97rPmfTOjXfnE4nVUh{faXJLgjB|0;X|Wi9&P3jWJ`R@__(s^@pBG{b z24-Im=L+xe<6iw(i z8CzBPLyJ4fIodg)>^rA{pXRs1#esJgdVxF$U<;V6dt?nQ-Vw*nBS5W1r=!{2(iJHm zVYiIBX&-IZ4gmWR1h88awuS7kBJaHoeFjlLN}B;|$!7izG?jjIelwQ~ygR>lkCB0z zLp18Rjo3|npj@yF@4j!NvP;gd0Oj~%ukt|a~azWejSy+s(0bKs-QMjBe<(@p23O?f1No}M1Xq#S5drfzgB|kul{Lbi?Yw-Fh zRPLz0=`gDHR$bAg(xEeY9C#y@3MbBXmN@E~TsS+yDd}REt5EsjnjF%km7#uQErA9r zPL->?_@RC6KyI>?`1lhH01uy8;(moGWh$c11#Lxl%GvjqJcroLmLLp4_T|YW1HGbQ zs}kq#Ejz6dnJ&KBBYkSS zK>cM>yu3pDo|Z7$3Bgho$9URZj@vt312XTb|U}&QS3XA zMj;krGNaGkNFCo|2Rq?;XjyG-(Uz`vVv)pW#&5Xpy7Ey=Ikt<>i}h9^egh@MuBi;4 zfr!pOE$azN*4~K4=ZEVywH85p39-s~klFl|U*A{#Jy42ZV`^lpl5VWthTq7E< zxAb1-*_idjtL*zKO_jo&20U4xe8Bp~1}U!?2as>T_Va=tkv;UFej>x?(y$a|Yg!uy zRrY8n#Yceru`3BT+-OB+@!s{2FvgF5AQMXhdw8-0Dxl@K()8~6$>agMRHa~cgaimQ8?h$s? zM)eOeY`D>d3b0Htx5>bpb!*w`06_ab_a0ln@RU(KdG2UL0bYmWi@!3q7na0Vd^18J zhwecPwV&K|7PaX#Dmd8=?Wja5RC8v14d3P|b{k*aLV3B#&x3FN3p?h&UMYU+_nec4*70W%}NXVtA2S#T)N1J4dE}1Lnc8j!sFcqB)tRBh0n3l zGz$tQ#v;QV1w(o#=<>p?OBUfx`irpny_!exY)L%(wW!d0*B3HB6Kfcs0rY=m0o)?I z>UXEz?Hk;wl1$(r7m&Eosz=;mtQ1!s9WFOY~YwOUD+e zB(X;jqj<%Jw@nR&C=uEaNnzNvzXgjs;E-cp546|XKIo*Dbh$34R}>@G!r}VGjMh4> z19;EKW?(V9fM`&1ko_|1#3<%&ZhRs(M^C9_PWkA%>v*{+YA8PR;Z~EI5i@>$8yk?x zS~TPmHJix7rTT(7dcu8>duuv<=|8*qL4TILrlgkcV`JQ+q>8?;QSClUWW=3FFlx&+ zy^%J2{LjjRq^sW15?uW1o4|0hlcEwYcb6S%(#NoL_cD0z{mMEtNhV@W$U(^g3Z*Z_ z_Q*k&SkdhI^ZTdcCCZZf52;8)aNl7tbFIeMDZqg?RybL#fOryCi38{Hes4erP)*^tlb@YWdSq6m-}fC`wq1YNoM7Si$dTHQ2S0;6`dHkNS$s|EfW`1 z9LW@cfX2~8cVaPTR!GBGBTIg7nfgegxrgazC@HaZD`Zv~3#wjYSEAI^W{VP16Aw)e zRacl>8E91$S=IKNLM%|iSvF$lv|`k9vQt~_ssMY-MbUghd&pf+i>4pKQ-Tcvl-veI zvnz}lte08NE!11*uI6h>!RzokY8xr3o5J?C;@%`S`DSkrSezF>5zraQVI;N0D(rf% z@Un!>DGRIwK`D5* zr^medub_WtKD-V#=%aT$+M8YQq}PEogfG|fhVQ7iaonl9oAoK z9jsmJ(L!83(s**_=X$-blv#a)JBqTs1!Cuj zK7$XvW+9R|31TqV5_-QMt||V0e^+iH|Ap1Z;aQ6ERwZvMkD?!N}v?v zidR>g13VdzWJJvdWK~yo(DubiKtTY5B4fIdo($~OC9=vZ8 zNeCRx1>VXJ7B-k?SD9#Ux7!0<^vzJX$WN%aK&?nQYV94M7olOwL*O~|o&Vfjp?Du^ zG#_?E)X)$h{ksp0sRNwe#~_P6V0)edV6L@catfOAwWy)_+V3F96b;|AIyL=Fo%F|070NJlbVo{5)iI3vyAXw1Z zvEYhv?)w9CKFY(ZJ(Ds9^YF9ToyD~p(CUoWj?h+VBO8}kcpP}Su1t+8Vi=7pTQ~4t z-J5S6G%m7`Ni5p*=5^YO)#-nb2C{6BN1Otm7Exa#_`WxK`^e2Hh1NydZC`Gt5V`+e zC3I}(!?#BW?s2k-rZt20x6It&+9rhm_Tl9K*bW!K#6o?VS%kM+1{As*d8I36g3#dd$n9nh$qx~aCQ@MY%q zvu4(K9bFkMi)bPys64b%0-J3eh!0%Du_*gO74^BhUmCr*VW~%k--{%jCR6oO&L5?{ zuo+Y>@cfwG2oZfM?^Z_dMGUiGla9@&EmvM9y$NiQ zuIqh>CBjW?C>zO@W$F=T?7uU(s|+oC*_N%MfIAoj<^b; zd0sNp)G3|2qX=yDqWi}s!j**9DeG^brGCuJLuOJ_JfTJT@DWxX@~_=|*lfqAjTPJX zlBeB!^$z~|07^t2S~?BJVsqz&7~0}(I4}jipx_~8v|9XCB0i*nde|e+NP2*BuQ*S$ z{`Uwd@jRra$#^^==aOO_Q9w)h>AuZ>4FCn4l7;|7IX!@dcUF7c{5NZo@}a)_DQioF$2 znkh6Ncnh8I?nI7K7A>q-_AKoOEdsimrEwEb`>i^@;#A)VI3Pc5TcwX90t)qCF8t(~ zB~SZ&J!>G1*Ez#k$?(sCrK0{uL#NHL>nGckD7o2j-^1VU4gqSFq9I2})4+Jk{#t#J z;m_F!cgU8jq_Doj$=l)927hK2+=hy;IWm-MrvM!ZA^?fl;J~eTom4-j?!Q2;wFBbO zzIBSUS#ihr9+}CBWVPU*AeIbvWR@Gn^H=8b`TvH^3+M~xKkphinGfUwhvT;xM-X2n zbzyMV>Hz=!N5n84^Q{fp_x8Fb`?cj>5gac#C&s)gcXx@Yi~GX& zUr^UC1zq8@nyc2MamUvep%7%=Xt>p<)pt)eLlADE>}HM$KQ)7_QC_{bC;!cN7XO$| zl=ww#UHyifxU2Nv$2+6(q|(5I_~3n>&)H4TDdq-^txXFJfc5DHrg&0kr-pCMebbUJ zzWnGps`XRB*lZxi=bUbY86Xtzg^pcHkqB;N^(P1v=pvjCneV4I#Ov(d++$&s3z`!t zXdQWHP-i`2v>*KX>1NVMs@pv1cRbGf-R88n2W zQX2bikKGJ!7oQP)pQhA_W~_i76E?elhh?Ie`3pM1Q?MmdPg*2X7^Q3Xl>LjZ^fwn^ z^(O1KYX}?xB1}ldLOMQ_e#esjmau7tGPHeuN7r*KE$Y{9OR7J3^NJiR?z3`I(0@E6 z`s>fFr_>xn2SdC}>S>~_x<4Qk7WyWjCMJazmEH%hHkm2+ZYL=7!K8^e0$a=Ht*PdY z$6*e*mRjui`}P0+si7Jo?KjmtVeC`Fr?j(Z``)Dc0NZu7yng>w1nLFf18neHHn81E z)IL85Ctd;C3j2RV4S4{McGBAH!ta;x*X=$R1L*nLQmRf{U&R^gML;4hPjCWq!=Kpx(Y=v;o z?S8eUve*%1qdzMF{=bRld!_oW7ZMG$x?Pg`fl1MaWXVtl!x;%%*VUi~s;D1x&rRL@}hwLAIO;Qaj{Q6jN3L@?$}S|!c^ zUB<0n{Q;1^{wpA*60*6&{31K79r827np7T`XFl;Y$nI4MPtOEF#CgX4(|M_#+9PPw1T`9id=a4((C1eLeUE zXeG&p4L^b9GXQN=Sv~5W=!oU#-}iy?P^N?T`OUoKX1iye`(XnGF1KUaoTpcL46)?! zBEk5NSd6kID0$J@Ns^Dezqqde=#tQV>ydtPzt)L&T?h(=i>3{d|BYi<}+mQN!{8L_pcPCcT!eI%f`I;AKGoJRYg zcrmeTZIdyIT5w7?l|nJ!54qpS3!ny$AcMLOcsU6i`PC{~ZE*o$XH|eq5`k3roNEum z`%<>TYu(@T7={<-zMcVwJzX!>y-N~mZ`-SXeQ!ejAVnVF-0!+F?N%5BSKWgqZ(#vd z%DUi;abUxaKJf@=KwBdL(cATQNjk}e765>i!ykBT6E&Q+XqiP5Qa zsx<2sFWv1(cKCk7zF_gfwLN6fYulyFfOql*$emduFHD!wuIRs_2gPx;DgF5e4=Xyy z`_Je{+*Oty;YG^b1l(C;QlSKp+U6u62454=UVdj>fK z7|dr6>o!&7IhmdcF_m{}BTBqfGli`?hwoJS6;Y$EYbQSe%g9TMRed{z?NE~HgYP~K z%!&Q%-aUopz5A=ji#>^4_ukPEl4>j{Gf+tZuLGox3pYcTe>x(1&0@94o5c5)$*iBENkaf4 zaX_g4WKSP5#elwC51`wftV5Y^3##VyWhFc3^<~rs&J@F}h;qz;E{O+^L>g%23g78w z>Vm|(QZ`420i(hvL1t=kx$3_uL`dW&D&cH~HG3=Q1V4rcIN;#8XA7#=eAT!p#t&3 z$?3TyV~4iorUf~f9)&k)M1w8zNH6@(qoZ-d7vKlsKH+`1f&8*?Ir%@rD72a8GC&?M z?E=hWVN{D&m>*uB4-~fBeE~q=ukusdNMJB2+nqydkJe>xp*CX9<=Drti(MiGToRF+ z#@vr2jAK6(1>ZyJ$}YCfJWZLl`rY|mEP+K9l^x*yz%A|L+mWHUf4-}%jMu}?6!bH| zh;v6K$yKsWt@>qrh5#(KWN72A0u!mJMZfz&^3YwP?mJsyKEWUyA{oqru(v8RH2r3N zcl1dylYH^Kcp)0XD?u+N*vRsgiXur``zxOnW*h)dZ1tkv`M-#XvRE8FfJ}Y6IdBdg z)-d(Rv>z<+q*K$ZWq%j1{#v6QTN}*UavKHDc3LGMbK%^oDBxhR+&8l_E)g|CB|_A^ z@o5n5yiV6QAW9}7FBlKq8pn3i;oiMA*XBU{TP>-&~ZEAcf_QKIrP z(g!WgK`$>mC?s6&6KJ=|-+Y-#R;5>DY-bvytKTPd&O%*DvL(7*zw%Wg4-LVr$hgF@ ze*XOx{g#db^AJt$TAZipgaBFF59i4VkDiVm9jSpP4u*gwa#ZCEPwet?*V~zPKG;|4 zCt+u(<|EH=zXu76Ms+m`(HNUAr2($Oo^|(MmQWm{Vc4hP4BFzIIGrSk=b+6EmJT{m z!Vk6UGYFo7Lha+7(jMauc2NE4Y^m#VQ=b5Nn*SMO6~idY-hY)#u7@@&xh1#nx-58X zyL{D&vVa}gbL8AHAT9vv<>FB<9+kfE-4H_!yR4AEMixf4tgFx=LYTMfdT#QiyGsf$ zqd9CDPFD20h?s~E{Q%o}+)JmP?8M6M;$U_WV^O1x-6DZ8q~fA9C6mRt2_Q*L1_Fs} zNk}r?DCowk3fS8b_e^4=GBfbEPIkNLh^_20o#uP!;GMfCuZH^9` z1@YQro!5V;MgE#YusA(wf?08w4bzCT1Nxr1;)3kIoWqXM68pon9%s+`cGV>;ge{F{ z-S%MENRXX`myW|ov-!C=_qQ!4C%?-j0_irh94JTCnO|`PU}*J;`Q}p@Ejn01^z^Q_ zPGXZR04ig6V_MH-Q+*&G4cNxW4@v~3)e3>Z#g>Y}qPnw2A#9;84*9cP$fZA?LAI&t z{4AZ(!~CiQ;EE)TE*BfLdxtHY_6Khm`)e-s8wqAQCrf-eswt(}F2dCH3CHa44^1Pfhf{;SXu*9{f@Xa<_4 zEfEDI^0Yc@?$INND8?WOUCVX0JEXuNyV^brIUiG7v{)S%_?WOBD^R}$CZpm_~)x+0zQ+ z_n(e~`LSOvHFxAjsO?g)1WLqfu!S@XfTmol9x&MXK&Xe?hUdJif&elfGVx;xGR z6V<7>;tC=!zBp%r5TcW4+6tDnW+nPrgU%`F)={nga&VOu5(kFpQc|LL@0-EozI#cx zQG_^j`TIIGRDK3G3IRrqO;}6MKjX!o-I98`E$-~`X69S)xXR$-j zpt}HiFu;qDtQc|0iXvhRut33%P~O%61)VdxcvA2j)!bjitbc?%A#l;@3F@#cAk@3P z1B^&3aSU>kJ&=fQQx@;o@Q>i=cdT?-9TJMO3sr_%khwhk;VcWuDYFV_3vB)_EKp+9 zwTuZ1A}%KVGXWMRc%2w*C2Wm6%%1Sg{~(P0d0)f^cnMbup6$ z@D>pw*^`W- zAP`7;LIPUFi<%fn_l;=wBd$J;5~Pq+1XcEb;5B~*i9Di8ZLd!K-c1DHFG|1v^3S1) z;DKOsLvF=y6w(wXdh_1>H&?49|NW6xNWkO;KH({wKGNR&P%JS6N#Q@naqX|MyCZ;n zmWi{)lM)^trX;%&PuKzN(uKP8?OeBObfX64`xU;0+_xFG``-U--sTruh^S z(BKKp8UH=5*b!)y;||{KDEG)T6IlBis&z3me!y(11_wuX;KXU11!*RL%aP~)exzUX zY1h9!o!6Y6TZeTFRQ~1ht@_5BhM%pb(W%4HyZ;(2zW*Am8psz+EWDynA8_E5#p=|q zjodn#Bh2LP{F`EsF>ctxeP_yrhCqMmFja&E?XOwvwMk_j%XKfjtGw@wNUwWQ{5J61 zg5BOnXGy9tK1;lhPR<&f(YvWlyQ4LU!Mo0y2CtA1mQqx@u+701u}o(k3t$NHmtn5VZ?9&Oh=Bq0Rfp|8!!#=P!@kCNQ;Gq^$2UH7q06w?f(;zJ?kiX#(w=$A?;_se>D4j+^MkG12a5;-L1fIzzLgsqPDd z@cRg=4}I%Z_rGI=yGGi%v%HVa&eC0P`e?~RwoM{pzN%bgpiJ9XOIUT|3*Npo%GB7E zQ%bsfADwhyVoRpF*A&&0{(Ol0g^$-<*q*YK2NoK&n&vxNqa&2J(k-0iCyOS;X~Rp7(M7_>0r4ZC3=%74%em&*-|M>~FyO7ZD znH65GHZsF56MryV$(R=P4n+-PQKPW^ptSJ62Tax$#HnMM8#;YOY#b8wMi#DWjM7c40y4XDcMhQ5K#RcVTNx~>8Wmmy zZGRzfpeE&~IUMiAktPmrj3}UAB}xJ-RloNw$fm$=U%@9Vg&gABBRujrie6S;=_3ne z@a9d!IS8SXT%+4mBcPjPBT0VF!n{7TcF`Yl#Vu738dyGb2394*X-uxqI>vK&Qt=BH zpxurGK=c3_ay|p0=p>$my4e6ruAe$F%^Azqwq1hZ!Zg*f9KqPPK;ax*8Eu+|E=8}P zbu8y{0ARxIK!4hD+9%g1f{}dX8$c_S7jgjtvMsoFu*b+|d@&-iY zPQaS1K(cc`XzchJpfUI7m)WygvudQa>#1+Y8cZjh0eI(KV%@hFyZpepAW1nL+};M@ zzoCZ;K>S#BK>*O^;l_e#rEbte>C-45Iw(kusO`{HHDA?tX382V9FcS$jZ|6cz_GS3 zBX80?DC2aN2eR&Udv7WY*Hgp0s#xR!I0G7s6(^Z}{S4Q5~A+hmoH%N9!34dk+)Mb(p+g&<|M^#?b!qx+Bk zSlWL8P@plWQloanz-Nlo@BUQQ_f=kFNtqf#CFGlc&S%u`^?g}V+6g^sf}DRjP%{T& z_o!G@Bj?4jfr@)yLVTS*v9?$k6Q`fC>arOQIBVO`qjqOmM1z%{0-YPGU-OsXwEZ8? znS3xK(+M8IN{&p7JiUPc-01k*6RQ^9h?in8&PMZ#mzhEK!&Nv6Lb~NIEkh)aD(@EE zj=(2I9`*qLHi^ADihU$by`T)+>cPpT=g=jg|Aac%r$qIxj(5Tgvf?#U%5#|+4qhmN z19Q$#i8Pr!!vgDCf`dR0HnhmN6olLt5&pFRfB|$yI%su!smr`8Q#1mRN3Y3z-XX0* zhEP?SHZ@SOz&=UkUTuvO<~&}IxKRgD@(|l@sNM+1S$1xD9<(bA(wdm$3!8R1fcj?( zn%Qx57O)>o{&)jL+^1qX({=r=hd^Hn>w<#Ahi`;kh?~coo<@ouWNBiWhmblf+5*>B z={I2pv*->8F`)BNJM_ZQ-t7%qTwiIqYxr<$8kVcwsPCZI3Gg}_^t=%^|8C;|>=)XY zYj@}F&S+KVsCzNg00_1JQP=f%0N{G1wV?)J2;^G-6I8l`%bpCg?BCx4iaU#1Vnah$ z%^i^!s{w-J=y9ZeESh3luK^LkhrTyUuC{b;^XmOWJTWVqhc+)ttRh*p|kc$CE z+qUb8#LkXXGpRUycq;AQm%=6Ie+?RRiN!sFvi#upR0e5V+NA#05Ehx&tiEk zbzdxIU5j6*eyW+w-qQMt7rBY{%K%P6mQ|86td_(e*bMdntV2u{ZQM}|Qs(7uUlKLC zTs?8`%47_DNv-AK#^cUFJP+D21$!sM+iM(zzQmD*KIXPaBfwQtLjY5G7cyZxB+$M% z>eeMT@Kz0);+Kw?gigSB?AFM<<*(bRgMPXW&sABXs-mdV5MSDbFf%nGdJPq z_`ylb#PCGc-t|Jg7Cy(5^e(+IS=0o=h;A*`l5&tY;NjrhrdMg#P7jvlkGF|iS==3h zPJZ|=sc_J|MQWe^7>%PrKBG-LCw$XRX#~AQhuBd^wa6ur*yfWHP&F_&)3Ip-ZEOLe zsnv|-`Z7?5vYZ{w%^uwT1(3fo^D1M^S9VXA7!`K;i^b6D%^Zq#+SYZh_w2=F<{-PQ z@)4w)KdNMX+4aS32i~zVqG|D^)ZGLCBDIDS)L67j7XFk;UQ@m>*^J z-hfVzqw}WZDm?gcrKTXOkeP1OBuDzZuIv|HX)6`2zVH3x72N3x-)I20{@}piT(8sO z?K)Id_GRWF$U-OCtZsA2VOi+JYB?+WHSLyW6jZmE!BtE=T0Lv8r2;;Qb=m7Hwl`w6 zGZAVZetyettGsSB1(GfiJ6mg2hA2~D3c{sMh&lg9dRYgB{%OmbdV44-SPf)C(>?L| ze=vLg$fADd_gxhG0*FVLaSm4#8UL%kvYNXpaYNMj<6>(eB^_*tg1NXqp>mCa_n$G| zDx0$R{ot0>$TETxECD|6xC3&x|Ee6qCzW&{R`+?*e0*)1r^2O|$1B$;B>#D7J0utn zD!1UE1g+K(=`P&el|%FI!RA?Xa2^!ANntWPIs*s9-+l!Dbu(6QvB0zjFn>bf@6-d> zFJt5`X}S=;DLd3IqPp^ZFJv|}C8CjWCxC?96_j3~0KHiJF{@h;Dyu+^0}n6+;U_;L3^ zv(i#Z#uP_B5K2+vQ&F34Yfx)Lgu-32I1~ejG?k5f|MyFWD>+Ai8PRG(A}BuVT)sfW z2=Q;G5EdR;Q}+Q<)UE9DuQ(EnasrfxU(rzr3q0ZQ=(5Bi@!MVtoBtmy1krNz}5ObsL=js}k( z869Zb6X<=n_dl;KYF)=k0}F|#4ZW*L1>qPpUw#+E9iSvWFjvY+nT2bR#}tr=J6%r{ zU7*_KGqyxU#eG0i6>CUc31znCvcq$0lW;vGM_ZWJ2hs!XB zbX|vMKW4#68K~dO^=A$()={CWQs5sGUhfv%WK`e1Qih1r$R921O;+LR1JOd(XnMdh z$ygs39RFcAzpfKGBouDieQbJvEa4@2< zJH}KDF?6=AnK}Kw6dp;>iobqtO+^uY2{-|4tT2c#2#DuDKK_JJymVn^Odw#x1-^ZH z+O~omF{&@m9^6bX%PRE4hjKr`g0WYLB|al0AaF44E-#{>-?+iz%Sp`X}cF z@V1!d>7_hB&r5i6nGLPqCSdPjB2D~rSoXrsDcbi98%%d(C|pxad~ET;-lZE25Bsp3 zDjd=a^|nHUM?+V?v2Lw=W$BiXl=QbvgL736Hz`|3U!Cfw$q#cLAe9I z@&%XxHekJUGfOws0|cr5o7})Z8M=VoHGHkv_GRe|7g(xk`$)pIYj?l2*h<;i3t(q= zARN9YO&8cEZ9`K%%elnZumBsAI0>n{I8*f zpv8JH%S*o-67v&Txj)SvO;C4YIbGzP3L}v z3Rj)U*0n=tZBaxJ;Sfw5f53CzaAC6zw7D$WW0o}wra8rzSOpT3YjgX2FK~KaEOYLB zAvNHJ0W*W_x%vk%DXauP`fvi9t348tFkv#Soq0!IR{RhqTRbGGH#C;$asnN3tXo|PK8*JRQ!{Z{;b-;Zst z$66KR%7T1s{v1msAd16l588imkCEUhGk^t*!@T6_yBjMvP<9X*v^yO)kt@*{FIn! zmKJiTqR(L$nAIg`i!sp>(yji6=o8){Qg`885QA)p|yNiktCJUpD7;Bq=yr1#sQ- zf*UCj$?z6fLSfS?o)x&$^bp+qx3`Ep6}@Q>LNAhE`hZBY;@w!5dbmHdyIjq11#|hqZPzupFkB|irA?kYzHMj`BIja z*S0pB*$g`b@p(yWRV2h+JbZ>xjeR&>{D_Y%EQ5{5#o~-XEBJNhHlKsd``1GaT{DAP zox)c3?q7P)T@R{$UBCCN#04sKG}N-Q>!wD;rn@|E=4|qk-iVkQx<0?Xb4;O5JjFD+ z4ZMA71}?AhpkBSodWvgVa0+iB9_eNAvHK+2S)x=SP^sRAf=CNqtAiy9nTp5q40FlE zdEoSLB3}3QvGs`FaY=|e!6?F$mhw#KH%vO_r>& zUhB#)fUi`Y+ubgok1aRd188OSfjL;pijhVYoB_zPQG)|at|#INg2>_HF)f!6E)6V} z9|8)4^tV`OMQw6|;Hn((nI6bsUr$#)bJ-HFGv@x7F4hwFG)d7IxS*w=GUcc-bQZRfQBvLo~Mee+m z`3}u5?t4VM+Ze*e!Cw+mwnu8>8% zMkXsLJ6aC;wy1!jYE~X;jz9@*IpY@cnE&8J5MuCI-s^2;u)0J%bvruVHo@rB8^ANvK=F|oSWVHn*5v1K`pMvW^7{> z=f$m8h2nEhV4jrRW+3b%d_L8$)i5W4>DSwH#zLs~SgO-W-(g9bM<)Bl-B6+s1&DpU zn==YdOwArh4b?M@+`#etNN57=xS1X=Qyil#7)+?Ft3h6TU=4q)$^hooco z>uRPxpugNzSozTMqEU$u^0-O@L2IX{cx2QS2r&=U^u6HZs-UUMr(vZu^*yaauF(bTzj3e&y7r>CX116tPvDT|JmGuMatKjP(~t2VIxDsbFU&VeB{TzRtca&= z%#f;U0z4g$Jl#u1^46=&8-PzXhcwZ(4n&$??D2PlFs|lyc>~pFPZ(R7a8JNmDdbf` zSspw^<2!6@p5^d7v)2&Rw%r0dD@~~zTR({^Ux^TyW>n@wj);FZ#-sE0f z=LJG`>38EP0+B>?JwHbKqvo@Jo4?qWOVIbeieC#9p3>NIv*np_K2))H@XEL7t1?Yk z^X%xg) zviJa9c&BfglAxFL0LnEc!}B>-ejnAP)-W+9nOX(yU#ep>{$R=00b|N~7NL3?TsygM zMYcWrKwoQF7~6vE6C<*Vs@-+dm@Ey`z^SBd#R%{cZ_L;nlQe_Z@)~Y#8Z4wEF$K}U z6P#@Xd$KnTBo2MoGnwfVX0sXNp;P#<%0dGk5-e!e?}yxgbvjFL4?MkWsFiiCLTlxuK@Tt`JrU6L2H*$lNhq^DEmhnpe_ z4Q|!L+c#((PuTlx>i#4wzQU7z2?WxF)@!F)4+wy&C8mHrdLdNmD6cCfLx@mXVkE^t zX9e4EC5Pb#vy3Y)KEa(G?s_^COYi>#3pU;#Cgq=sX6fAp3sSaD=%YMmteURW4xDIDvH)|Hxu(H!XQ!m6 zsw&K2-3Mt4=rqn>Ym7?b*HAIg)FU{~YuCe1w#Eh`&Xy-Z_&b-0nVXw&uc!~7E^pyl zp?V=vM`s_S2bxd!rpWlFd&A~u@F5N`s(a@Jeg+E!tM12l^p{jkzVGH9og?o)Q{n)x zx?7mVXdNk?5XKJV)JMrf&4zLAVwQ+ULLDg0b7JE(6jYkQfRc8l8TF{N;p zPRQ3;GQ*I{^Ac&736$K;DO8fA3v*dP9Le;4uIst4a$whGD&)osoMzLLTa(LOsM87o z{TUeM@$7nfQNm`D8Z{-CcW-nSwQ1)#8(VNFboYABrW?dv05S`RiaD7)mcqq*- z)ZsTjtGPQQO*AKA>n7}J^CyV8lUsZC$T`@V?^Gr?U>T>*fxW=Un~`~wg{Te*GCKR` zOQISz2gJwce#`$uAo8tWfw!REQXnc3x9Z{ts40=yTr={4ve3&Z;WSJFdm^1*1_-K& z$zW&R{;#%`MUvB@3G-S;P~!Ghc%Zc7tRCl zQOS>H%Vp&VZ#xtFK0PnSy4uXO5-j$6XxE*6EN9NenYxcMNpcpAyi5i)<8hz#aH$eR zQ)(?-qN=JSypBAOM+uDcz=HpgmIx*W;XDFZv;5w)&8$~fjSQ-?lrcLOHhF&_VEgEW zN;_g9wd}US5VOS}^M;tSBS_5w?4BIU^X!kg%}KuZy@5*Y#%)y4m6?X=XuTk)Jv>=p zCRWXCw?abYG5@BXwiP8!U^#*(+jt4(VLe8@E@w^Hm1s!5wj7Gru-I zRk?g)Xx+zhS1p#|3ZY12>vTtHKD;P5CjP3L!rAv$mU@ir)*YQZ@wbNERSgRR=tqV| zc7zOcaYzx=^l|w|trm*lAR4I{jcRB@{KFf9#3Rh>ciYrf9&I5}s6L0V|5yx~HA;j& zhZN^E2ZosyP&lhxHl9y$r?QN(!saaFPp5C{TkoLy7?7g2%2N3C9BTh_U|-^(oYCxR zmG#`8zJpALQVT@3u{bemqB6cRY!7xW8~iieo{7|n(AVGeU7wrIukJfZQX&(TNWS3) zjnRxI22g;9QXa3_T;y50JF3tB1NWgiDi}xbYZ3|3?3S$gj=mJ=juyH`yX;h*M)Qd{ z*q7)!7fk&SVrYfA4&Y%iDV-$#GbQx(cYN26|3{#bs5Cl~%195wY|%ivqH~P3yy!-| z2*J8wLhah(n?~=c)_S2QV_p8xCQ+H*?&jMXzi3tS4X_p@-*>C|Xg@PbfAMmES&W^w zBBSla(IywneNyw^sIt;0slcd&)wD|(A`Tni%gtA373(|+QCl;j;>++J>!})3 zsJwh=^yFQ7(v(Dzh9=$y4+b~A9+?Tx%yaZNv!co3==K)|As8$N6O8sfQzsFDZ&&Df zkZ@XZt0?-7wd%>rC|)hCzD)@=#4BPDU}lWy#RP*vjP;}d^L&Y&WUFoz>K3!59Ov%r;#BLHwW~@?);doD!%ul4je1eW zpFi!~VsL{m za%<01LrWDS_KPoCl+7MZ;R4@1j~#O|!7JB6ig{u!!6^)k1rJX{lsq1{w>8vAwsFPH zLv>DHUXSO~Df5=Ml&k$&k2Jco+r7PCTM|a?MjVo>gnyox5(8YpCRbkCk8DB}?X59r zyt<0?XU(yk)Gk3({M2j^N56fzTH=Svz-+&5+dYd)qPYLD2WOaMJ&G&JC!|bomirNsnLAaZT$G`HF=;Ctp7F?78>D*7T&OMxy3yFye&3J!T z(b4&2H1(f75E%LB4KeELq={){APl&rn#!CM#EQSl^Lt$VQm=?|YMWN%J)u0ank`B_ z6iV5voT}MGLQ<#wP}fhZoy1y1YIiGn!{caak7tH5+h#z6gP3gTsXFF!Wt8!pg*x`b zMy~ZNuIp^5`md!GI^kfv=izxSdWoG|fj{et+5t$oC* zJ!b*@k)BVc6F&GYO60%CDH7U9UE@mI9HV;GUzy=xfi&F+0f5r+nZvn`Wm&*M>jJXM ziS%b*_*AYOG9pPM!2?GhqIZbEB z71NE&rC~SHYu9q$0shS+?&vpz0N@E!NPk)fVD?VVWW-s`Zx=!cJ)fui&4j${ms;#391Z^NRu^N(Cc8_1UAKToW!7Yh@T zBblNO0HJ?PMJyU@P4z;OR6rQtbTUa^f6danAeWWq`QS3=m>wO{m)0BJo=Z6RTJ0lg zmSkLZu>wKF6QYl0GXsJk(e&al{V^2sDI98PQR z6^zml&*G6BPze!tn%OGHIV%0D45Z@GFpg8rkhWgdH1lZViMRB2t{ZnOPAB==4nWiz2Y}4OuLkUrD?Y? z9xdm18rBGI2oLwK_hESv)JE!Vy;Xtw5#mte|IG8`;t?J|jv}mhyQv?Dr~kV?@m{b6(8y`QZxCW(ZNLurPc2LH=b0I#PJy8&C7bc<)bH;CY_{mnD!#=9Q4LO- zI+bH@A$j>F&+`4>yhE4b|8Lac;51lyR@HHl4lSPLfDGI>fsFV69?I}1vzVW6$OLdi zXzR81EbgB{hhUP;cFMLb7(e{-{1>iG9!i8SdZKqNMq2|`@JID~^9n82?S4NzmHK^jeoQ@W;HN9_?$uwa#!A7thlh8L zd~>7z?HFjdl)Yq;KI=`}=Iy-cVvw(4rSS3FB zemA#v(6Z$mD_5`mEZD;Mdet*x@h1uOrLTYa5WGLw*-Psxz07l5g7AMHcugIb!W^kM zq$1|5%f0rOU$QXT_ir`|-3@z5wOYO7UkChltU6|Zqd9xkt(wW1ie>OmM^pc3p@!|{ F{{gHsD-!?! literal 0 HcmV?d00001 diff --git a/doc/index.rst b/doc/index.rst index 09a2ddf745..5aea45d713 100644 --- a/doc/index.rst +++ b/doc/index.rst @@ -37,3 +37,4 @@ Guidelines and Best Practices :titlesonly: Debugging the Controller Manager and Plugins + Introspecting Controllers and Hardware Components diff --git a/doc/introspection.rst b/doc/introspection.rst new file mode 100644 index 0000000000..d3cccf7446 --- /dev/null +++ b/doc/introspection.rst @@ -0,0 +1,81 @@ + +Introspection of the ros2_control setup +*************************************** + +With the integration of the ``pal_statistics`` package, the ``controller_manager`` node publishes the registered variables within the same process to the ``~/introspection_data`` topics. +By default, all ``State`` and ``Command`` interfaces in the ``controller_manager`` are registered when they are added, and are unregistered when they are removed from the ``ResourceManager``. +The state of the all the registered entities are published at the end of every ``update`` cycle of the ``controller_manager``. For instance, In a complete synchronous ros2_control setup (with synchronous controllers and hardware components), this data in the ``Command`` interface is the command used by the hardware components to command the hardware. + +All the registered variables are published over 3 topics: ``~/introspection_data/full``, ``~/introspection_data/names``, and ``~/introspection_data/values``. +- The ``~/introspection_data/full`` topic publishes the full introspection data along with names and values in a single message. This can be useful to track or view variables and information from command line. +- The ``~/introspection_data/names`` topic publishes the names of the registered variables. This topic contains the names of the variables registered. This is only published every time a a variables is registered and unregistered. +- The ``~/introspection_data/values`` topic publishes the values of the registered variables. This topic contains the values of the variables registered. + +The topics ``~/introspection_data/full`` and ``~/introspection_data/values`` are always published on every update cycle asynchronously, provided that there is at least one subscriber to these topics. + +The topic ``~/introspection_data/full`` can be used to integrate with your custom visualization tools or to track the variables from the command line. The topic ``~/introspection_data/names`` and ``~/introspection_data/values`` are to be used for visualization tools like `PlotJuggler `_ or `RQT plot `_ to visualize the data. + +.. note:: + If you have a high frequency of data, it is recommended to use the ``~/introspection_data/names`` and ``~/introspection_data/values`` topic. So, that the data transferred and stored is minimized. + +How to introspect internal variables of controllers and hardware components +============================================================================ + +Any member variable of a controller or hardware component can be registered for the introspection. It is very important that the lifetime of this variable exists as long as the controller or hardware component is available. + +.. note:: + If a variable's lifetime is not properly managed, it may be attempted to read, which in the worst case scenario will cause a segmentation fault. + +How to register a variable for introspection +--------------------------------------------- + +1. Include the necessary headers in the controller or hardware component header file. + + .. code-block:: cpp + + #include + +2. Register the variable in the configure method of the controller or hardware component. + + .. code-block:: cpp + + void MyController::on_configure() + { + ... + // Register the variable for introspection (disabled by default) + // The variable is introspected only when the controller is active and + // then deactivated when the controller is deactivated. + REGISTER_ROS2_CONTROL_INTROSPECTION("my_variable_name", &my_variable_); + ... + } + +3. By default, the introspection of all the registered variables of the controllers and the hardware components is only activated, when they are active and it is deactivated when the controller or hardware component is deactivated. + + .. note:: + If you want to keep the introspection active even when the controller or hardware component is not active, you can do that by calling ``this->enable_introspection(true)`` in the ``on_configure`` and ``on_deactivate`` method of the controller or hardware component after registering the variables. + +Types of entities that can be introspected +------------------------------------------- + +- Any variable that can be cast to a double is suitable for registration. +- A function that returns a value that can be cast to a double is also suitable for registration. +- Variables of complex structures can be registered by having defined introspection for their every internal variable. +- Introspection of custom types can be done by defining a `custom introspection function `_. + + .. note:: + Registering the variables for introspection is not real-time safe. It is recommended to register the variables in the ``on_configure`` method only. + +Data Visualization +******************* + +Data can be visualized with any tools that display ROS topics, but we recommend `PlotJuggler `_ for viewing high resolution live data, or data in bags. + +1. Open ``PlotJuggler`` running ``ros2 run plotjuggler plotjuggler``. + .. image:: images/plotjuggler.png +2. Visualize the data: + - Importing from the ros2bag + - Subscribing to the ROS2 topics live with the ``ROS2 Topic Subscriber`` option under ``Streaming`` header. +3. Choose the topics ``~/introspection_data/names`` and ``~/introspection_data/values`` from the popup window. + .. image:: images/plotjuggler_select_topics.png +4. Now, select the variables that are of your interest and drag them to the plot. + .. image:: images/plotjuggler_visualizing_data.png diff --git a/doc/release_notes.rst b/doc/release_notes.rst index 3dec704f23..efe81d0567 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -27,6 +27,7 @@ For details see the controller_manager section. * The ``assign_interfaces`` and ``release_interfaces`` methods are now virtual, so that the user can override them to store the interfaces into custom variable types, so that the user can have the flexibility to take the ownership of the loaned interfaces to the controller (`#1743 `_) * The new ``PoseSensor`` semantic component provides a standard interface for hardware providing cartesian poses (`#1775 `_) * The controllers now support the fallback controllers (a list of controllers that will be activated, when the spawned controllers fails by throwing an exception or returning ``return_type::ERROR`` during the ``update`` cycle) (`#1789 `_) +* The controllers can be easily introspect the internal member variables using the macro ``REGISTER_ROS2_CONTROL_INTROSPECTION`` (`#1918 `_) * A new ``SemanticComponentCommandInterface`` semantic component provides capabilities analogous to the ``SemanticComponentInterface``, but for write-only devices (`#1945 `_) * The new semantic command interface ``LedRgbDevice`` provides standard (command) interfaces for 3-channel LED devices (`#1945 `_) @@ -87,6 +88,7 @@ controller_manager * The ``ros2_control_node`` node has a new ``cpu_affinity`` parameter to bind the process to a specific CPU core. By default, this is not enabled. (`#1852 `_). * The ``--service-call-timeout`` was added as parameter to the helper scripts ``spawner.py``. Useful when the CPU load is high at startup and the service call does not return immediately (`#1808 `_). * The ``cpu_affinity`` parameter can now accept of types ``int`` or ``int_array`` to bind the process to a specific CPU core or multiple CPU cores. (`#1915 `_). +* The ``pal_statistics`` is now integrated into the controller_manager, so that the controllers, hardware components and the controller_manager can be easily introspected and monitored using the topics ``~/introspection_data/names`` and ``~/introspection_data/values`` (`#1918 `_). * A python module ``test_utils`` was added to the ``controller_manager`` package to help with integration testing (`#1955 `_). hardware_interface @@ -161,6 +163,7 @@ hardware_interface * With (`#1421 `_) a key-value storage is added to InterfaceInfo. This allows to define extra params with per Command-/StateInterface in the ``.ros2_control.xacro`` file. * With (`#1763 `_) parsing for SDF published to ``robot_description`` topic is now also supported. * With (`#1567 `_) all the Hardware components now have a fully functional asynchronous functionality, by simply adding ``is_async`` tag to the ros2_control tag in the URDF. This will allow the hardware components to run in a separate thread, and the controller manager will be able to run the controllers in parallel with the hardware components. +* The hardware components can be easily introspect the internal member variables using the macro ``REGISTER_ROS2_CONTROL_INTROSPECTION`` (`#1918 `_) joint_limits ************ diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index 673704c868..e3cf55df6d 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -22,6 +22,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS tinyxml2_vendor joint_limits urdf + pal_statistics ) find_package(ament_cmake REQUIRED) diff --git a/hardware_interface/include/hardware_interface/actuator_interface.hpp b/hardware_interface/include/hardware_interface/actuator_interface.hpp index 87b5202734..1f693d1d34 100644 --- a/hardware_interface/include/hardware_interface/actuator_interface.hpp +++ b/hardware_interface/include/hardware_interface/actuator_interface.hpp @@ -25,6 +25,7 @@ #include "hardware_interface/component_parser.hpp" #include "hardware_interface/handle.hpp" #include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/introspection.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "hardware_interface/types/trigger_type.hpp" @@ -93,7 +94,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod */ ActuatorInterface(const ActuatorInterface & other) = delete; - ActuatorInterface(ActuatorInterface && other) = default; + ActuatorInterface(ActuatorInterface && other) = delete; virtual ~ActuatorInterface() = default; @@ -522,6 +523,22 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod */ const HardwareInfo & get_hardware_info() const { return info_; } + /// Enable or disable introspection of the hardware. + /** + * \param[in] enable Enable introspection if true, disable otherwise. + */ + void enable_introspection(bool enable) + { + if (enable) + { + stats_registrations_.enableAll(); + } + else + { + stats_registrations_.disableAll(); + } + } + protected: HardwareInfo info_; // interface names to InterfaceDescription @@ -548,6 +565,9 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod std::unordered_map actuator_states_; std::unordered_map actuator_commands_; std::atomic next_trigger_ = TriggerType::READ; + +protected: + pal_statistics::RegistrationsRAII stats_registrations_; }; } // namespace hardware_interface diff --git a/hardware_interface/include/hardware_interface/handle.hpp b/hardware_interface/include/hardware_interface/handle.hpp index 5c4809e2a6..ddb9dbd99c 100644 --- a/hardware_interface/include/hardware_interface/handle.hpp +++ b/hardware_interface/include/hardware_interface/handle.hpp @@ -25,6 +25,7 @@ #include #include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/introspection.hpp" #include "hardware_interface/macros.hpp" namespace hardware_interface @@ -203,6 +204,24 @@ class StateInterface : public Handle { } + void registerIntrospection() const + { + if (std::holds_alternative(value_)) + { + std::function f = [this]() + { return value_ptr_ ? *value_ptr_ : std::numeric_limits::quiet_NaN(); }; + DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f); + } + } + + void unregisterIntrospection() const + { + if (std::holds_alternative(value_)) + { + DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name()); + } + } + StateInterface(const StateInterface & other) = default; StateInterface(StateInterface && other) = default; @@ -230,6 +249,24 @@ class CommandInterface : public Handle CommandInterface(CommandInterface && other) = default; + void registerIntrospection() const + { + if (std::holds_alternative(value_)) + { + std::function f = [this]() + { return value_ptr_ ? *value_ptr_ : std::numeric_limits::quiet_NaN(); }; + DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f); + } + } + + void unregisterIntrospection() const + { + if (std::holds_alternative(value_)) + { + DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name()); + } + } + using Handle::Handle; using SharedPtr = std::shared_ptr; diff --git a/hardware_interface/include/hardware_interface/introspection.hpp b/hardware_interface/include/hardware_interface/introspection.hpp new file mode 100644 index 0000000000..d25b71c2d8 --- /dev/null +++ b/hardware_interface/include/hardware_interface/introspection.hpp @@ -0,0 +1,54 @@ +// Copyright 2024 PAL Robotics S.L. +// +// 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. + +/// \author Sai Kishor Kothakota + +#ifndef HARDWARE_INTERFACE__INTROSPECTION_HPP_ +#define HARDWARE_INTERFACE__INTROSPECTION_HPP_ + +#include "pal_statistics/pal_statistics_macros.hpp" +#include "pal_statistics/pal_statistics_utils.hpp" + +namespace hardware_interface +{ +constexpr char DEFAULT_REGISTRY_KEY[] = "ros2_control"; +constexpr char DEFAULT_INTROSPECTION_TOPIC[] = "~/introspection_data"; + +#define REGISTER_ROS2_CONTROL_INTROSPECTION(ID, ENTITY) \ + REGISTER_ENTITY( \ + hardware_interface::DEFAULT_REGISTRY_KEY, get_name() + "." + ID, ENTITY, \ + &stats_registrations_, false); + +#define UNREGISTER_ROS2_CONTROL_INTROSPECTION(ID) \ + UNREGISTER_ENTITY(DEFAULT_REGISTRY_KEY, get_name() + "." + ID); + +#define CLEAR_ALL_ROS2_CONTROL_INTROSPECTION_REGISTRIES() CLEAR_ALL_REGISTRIES(); + +#define INITIALIZE_ROS2_CONTROL_INTROSPECTION_REGISTRY(node, topic, registry_key) \ + INITIALIZE_REGISTRY(node, topic, registry_key); + +#define START_ROS2_CONTROL_INTROSPECTION_PUBLISHER_THREAD(registry_key) \ + START_PUBLISH_THREAD(registry_key); + +#define PUBLISH_ROS2_CONTROL_INTROSPECTION_DATA_ASYNC(registry_key) \ + PUBLISH_ASYNC_STATISTICS(registry_key); + +#define DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(ID, ENTITY) \ + REGISTER_ENTITY(DEFAULT_REGISTRY_KEY, ID, ENTITY); + +#define DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(ID) \ + UNREGISTER_ENTITY(DEFAULT_REGISTRY_KEY, ID); +} // namespace hardware_interface + +#endif // HARDWARE_INTERFACE__INTROSPECTION_HPP_ diff --git a/hardware_interface/include/hardware_interface/sensor_interface.hpp b/hardware_interface/include/hardware_interface/sensor_interface.hpp index c99138fc11..58a8b4790a 100644 --- a/hardware_interface/include/hardware_interface/sensor_interface.hpp +++ b/hardware_interface/include/hardware_interface/sensor_interface.hpp @@ -25,6 +25,7 @@ #include "hardware_interface/component_parser.hpp" #include "hardware_interface/handle.hpp" #include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/introspection.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" @@ -92,7 +93,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI */ SensorInterface(const SensorInterface & other) = delete; - SensorInterface(SensorInterface && other) = default; + SensorInterface(SensorInterface && other) = delete; virtual ~SensorInterface() = default; @@ -326,6 +327,22 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI */ const HardwareInfo & get_hardware_info() const { return info_; } + /// Enable or disable introspection of the sensor hardware. + /** + * \param[in] enable Enable introspection if true, disable otherwise. + */ + void enable_introspection(bool enable) + { + if (enable) + { + stats_registrations_.enableAll(); + } + else + { + stats_registrations_.disableAll(); + } + } + protected: HardwareInfo info_; // interface names to InterfaceDescription @@ -346,6 +363,9 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI rclcpp::Logger sensor_logger_; // interface names to Handle accessed through getters/setters std::unordered_map sensor_states_map_; + +protected: + pal_statistics::RegistrationsRAII stats_registrations_; }; } // namespace hardware_interface diff --git a/hardware_interface/include/hardware_interface/system_interface.hpp b/hardware_interface/include/hardware_interface/system_interface.hpp index 4337f5fd19..7577d0ebdc 100644 --- a/hardware_interface/include/hardware_interface/system_interface.hpp +++ b/hardware_interface/include/hardware_interface/system_interface.hpp @@ -25,6 +25,7 @@ #include "hardware_interface/component_parser.hpp" #include "hardware_interface/handle.hpp" #include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/introspection.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" @@ -96,7 +97,7 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI */ SystemInterface(const SystemInterface & other) = delete; - SystemInterface(SystemInterface && other) = default; + SystemInterface(SystemInterface && other) = delete; virtual ~SystemInterface() = default; @@ -551,6 +552,22 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI */ const HardwareInfo & get_hardware_info() const { return info_; } + /// Enable or disable introspection of the hardware. + /** + * \param[in] enable Enable introspection if true, disable otherwise. + */ + void enable_introspection(bool enable) + { + if (enable) + { + stats_registrations_.enableAll(); + } + else + { + stats_registrations_.disableAll(); + } + } + protected: HardwareInfo info_; // interface names to InterfaceDescription @@ -587,6 +604,9 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI std::unordered_map system_states_; std::unordered_map system_commands_; std::atomic next_trigger_ = TriggerType::READ; + +protected: + pal_statistics::RegistrationsRAII stats_registrations_; }; } // namespace hardware_interface diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index f890b1bfe9..2e68a60957 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -12,15 +12,16 @@ backward_ros control_msgs + joint_limits lifecycle_msgs + pal_statistics pluginlib rclcpp_lifecycle rcpputils realtime_tools + sdformat_urdf tinyxml2_vendor - joint_limits urdf - sdformat_urdf rcutils rcutils diff --git a/hardware_interface/src/actuator.cpp b/hardware_interface/src/actuator.cpp index 790898cfed..65b337aa62 100644 --- a/hardware_interface/src/actuator.cpp +++ b/hardware_interface/src/actuator.cpp @@ -98,6 +98,7 @@ const rclcpp_lifecycle::State & Actuator::configure() const rclcpp_lifecycle::State & Actuator::cleanup() { std::unique_lock lock(actuators_mutex_); + impl_->enable_introspection(false); if (impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { switch (impl_->on_cleanup(impl_->get_lifecycle_state())) @@ -119,6 +120,7 @@ const rclcpp_lifecycle::State & Actuator::cleanup() const rclcpp_lifecycle::State & Actuator::shutdown() { std::unique_lock lock(actuators_mutex_); + impl_->enable_introspection(false); if ( impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN && impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) @@ -146,6 +148,7 @@ const rclcpp_lifecycle::State & Actuator::activate() switch (impl_->on_activate(impl_->get_lifecycle_state())) { case CallbackReturn::SUCCESS: + impl_->enable_introspection(true); impl_->set_lifecycle_state(rclcpp_lifecycle::State( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE)); break; @@ -164,6 +167,7 @@ const rclcpp_lifecycle::State & Actuator::activate() const rclcpp_lifecycle::State & Actuator::deactivate() { std::unique_lock lock(actuators_mutex_); + impl_->enable_introspection(false); if (impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { switch (impl_->on_deactivate(impl_->get_lifecycle_state())) @@ -187,6 +191,7 @@ const rclcpp_lifecycle::State & Actuator::deactivate() const rclcpp_lifecycle::State & Actuator::error() { std::unique_lock lock(actuators_mutex_); + impl_->enable_introspection(false); if ( impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN && impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index a99ae3db3b..e43c650d5d 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -611,6 +611,7 @@ class ResourceStorage command_interface->get_name() + "]"); throw std::runtime_error(msg); } + command_interface->registerIntrospection(); } // BEGIN (Handle export change): for backward compatibility, can be removed if @@ -668,6 +669,7 @@ class ResourceStorage interface->get_name() + "]"); throw std::runtime_error(msg); } + interface->registerIntrospection(); return interface_name; } /// Adds exported state interfaces into internal storage. @@ -715,6 +717,7 @@ class ResourceStorage { for (const auto & interface : interface_names) { + state_interface_map_[interface]->unregisterIntrospection(); state_interface_map_.erase(interface); } } @@ -775,6 +778,7 @@ class ResourceStorage { for (const auto & interface : interface_names) { + command_interface_map_[interface]->unregisterIntrospection(); command_interface_map_.erase(interface); claimed_command_interface_map_.erase(interface); } diff --git a/hardware_interface/src/sensor.cpp b/hardware_interface/src/sensor.cpp index 0ef4da36d4..87ea42790e 100644 --- a/hardware_interface/src/sensor.cpp +++ b/hardware_interface/src/sensor.cpp @@ -95,6 +95,7 @@ const rclcpp_lifecycle::State & Sensor::configure() const rclcpp_lifecycle::State & Sensor::cleanup() { std::unique_lock lock(sensors_mutex_); + impl_->enable_introspection(false); if (impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { switch (impl_->on_cleanup(impl_->get_lifecycle_state())) @@ -116,6 +117,7 @@ const rclcpp_lifecycle::State & Sensor::cleanup() const rclcpp_lifecycle::State & Sensor::shutdown() { std::unique_lock lock(sensors_mutex_); + impl_->enable_introspection(false); if ( impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN && impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) @@ -143,6 +145,7 @@ const rclcpp_lifecycle::State & Sensor::activate() switch (impl_->on_activate(impl_->get_lifecycle_state())) { case CallbackReturn::SUCCESS: + impl_->enable_introspection(true); impl_->set_lifecycle_state(rclcpp_lifecycle::State( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE)); break; @@ -161,6 +164,7 @@ const rclcpp_lifecycle::State & Sensor::activate() const rclcpp_lifecycle::State & Sensor::deactivate() { std::unique_lock lock(sensors_mutex_); + impl_->enable_introspection(false); if (impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { switch (impl_->on_deactivate(impl_->get_lifecycle_state())) @@ -184,6 +188,7 @@ const rclcpp_lifecycle::State & Sensor::deactivate() const rclcpp_lifecycle::State & Sensor::error() { std::unique_lock lock(sensors_mutex_); + impl_->enable_introspection(false); if ( impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN && impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) diff --git a/hardware_interface/src/system.cpp b/hardware_interface/src/system.cpp index 694e45f2f3..8f626f7c8d 100644 --- a/hardware_interface/src/system.cpp +++ b/hardware_interface/src/system.cpp @@ -96,6 +96,7 @@ const rclcpp_lifecycle::State & System::configure() const rclcpp_lifecycle::State & System::cleanup() { std::unique_lock lock(system_mutex_); + impl_->enable_introspection(false); if (impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { switch (impl_->on_cleanup(impl_->get_lifecycle_state())) @@ -117,6 +118,7 @@ const rclcpp_lifecycle::State & System::cleanup() const rclcpp_lifecycle::State & System::shutdown() { std::unique_lock lock(system_mutex_); + impl_->enable_introspection(false); if ( impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN && impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) @@ -144,6 +146,7 @@ const rclcpp_lifecycle::State & System::activate() switch (impl_->on_activate(impl_->get_lifecycle_state())) { case CallbackReturn::SUCCESS: + impl_->enable_introspection(true); impl_->set_lifecycle_state(rclcpp_lifecycle::State( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE)); break; @@ -162,6 +165,7 @@ const rclcpp_lifecycle::State & System::activate() const rclcpp_lifecycle::State & System::deactivate() { std::unique_lock lock(system_mutex_); + impl_->enable_introspection(false); if (impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { switch (impl_->on_deactivate(impl_->get_lifecycle_state())) @@ -185,6 +189,7 @@ const rclcpp_lifecycle::State & System::deactivate() const rclcpp_lifecycle::State & System::error() { std::unique_lock lock(system_mutex_); + impl_->enable_introspection(false); if ( impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN && impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) From 3e253fc4457b244ffbc86f593f804e8c95100b5c Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 14 Feb 2025 18:54:24 +0100 Subject: [PATCH 20/26] [CM] Improve memory allocation with buffer variables (#1801) --- .../controller_manager/controller_manager.hpp | 36 ++++ controller_manager/src/controller_manager.cpp | 155 +++++++----------- 2 files changed, 95 insertions(+), 96 deletions(-) diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp index 49eed135be..9df9fb56ca 100644 --- a/controller_manager/include/controller_manager/controller_manager.hpp +++ b/controller_manager/include/controller_manager/controller_manager.hpp @@ -604,6 +604,42 @@ class ControllerManager : public rclcpp::Node }; SwitchParams switch_params_; + + struct RTBufferVariables + { + RTBufferVariables() + { + deactivate_controllers_list.reserve(1000); + activate_controllers_using_interfaces_list.reserve(1000); + fallback_controllers_list.reserve(1000); + interfaces_to_start.reserve(1000); + interfaces_to_stop.reserve(1000); + concatenated_string.reserve(5000); + } + + const std::string & get_concatenated_string( + const std::vector & strings, bool clear_string = true) + { + if (clear_string) + { + concatenated_string.clear(); + } + for (const auto & str : strings) + { + concatenated_string.append(str); + concatenated_string.append(" "); + } + return concatenated_string; + } + + std::vector deactivate_controllers_list; + std::vector activate_controllers_using_interfaces_list; + std::vector fallback_controllers_list; + std::vector interfaces_to_start; + std::vector interfaces_to_stop; + std::string concatenated_string; + }; + RTBufferVariables rt_buffer_; }; } // namespace controller_manager diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 07af09c7ac..64a2a1594b 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -217,14 +217,14 @@ void get_active_controllers_using_command_interfaces_of_controller( void extract_command_interfaces_for_controller( const controller_manager::ControllerSpec & ctrl, - const hardware_interface::ResourceManager & resource_manager, + const std::unique_ptr & resource_manager, std::vector & request_interface_list) { auto command_interface_config = ctrl.c->command_interface_configuration(); std::vector command_interface_names = {}; if (command_interface_config.type == controller_interface::interface_configuration_type::ALL) { - command_interface_names = resource_manager.available_command_interfaces(); + command_interface_names = resource_manager->available_command_interfaces(); } if ( command_interface_config.type == controller_interface::interface_configuration_type::INDIVIDUAL) @@ -238,7 +238,7 @@ void extract_command_interfaces_for_controller( void get_controller_list_command_interfaces( const std::vector & controllers_list, const std::vector & controllers_spec, - const hardware_interface::ResourceManager & resource_manager, + const std::unique_ptr & resource_manager, std::vector & request_interface_list) { for (const auto & controller_name : controllers_list) @@ -1459,12 +1459,12 @@ controller_interface::return_type ControllerManager::switch_controller( if (in_activate_list) { extract_command_interfaces_for_controller( - controller, *resource_manager_, activate_command_interface_request_); + controller, resource_manager_, activate_command_interface_request_); } if (in_deactivate_list) { extract_command_interfaces_for_controller( - controller, *resource_manager_, deactivate_command_interface_request_); + controller, resource_manager_, deactivate_command_interface_request_); } // cache mapping between hardware and controllers for stopping when read/write error happens @@ -2430,36 +2430,26 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration & if (!ok) { - std::vector stop_request = {}; - std::string failed_hardware_string; - failed_hardware_string.reserve(500); + rt_buffer_.deactivate_controllers_list.clear(); // Determine controllers to stop for (const auto & hardware_name : failed_hardware_names) { - failed_hardware_string.append(hardware_name); - failed_hardware_string.append(" "); auto controllers = resource_manager_->get_cached_controllers_to_hardware(hardware_name); - stop_request.insert(stop_request.end(), controllers.begin(), controllers.end()); - } - std::string stop_request_string; - stop_request_string.reserve(500); - for (const auto & controller : stop_request) - { - stop_request_string.append(controller); - stop_request_string.append(" "); + rt_buffer_.deactivate_controllers_list.insert( + rt_buffer_.deactivate_controllers_list.end(), controllers.begin(), controllers.end()); } RCLCPP_ERROR( get_logger(), "Deactivating following hardware components as their read cycle resulted in an error: [ %s]", - failed_hardware_string.c_str()); + rt_buffer_.get_concatenated_string(failed_hardware_names).c_str()); RCLCPP_ERROR_EXPRESSION( - get_logger(), !stop_request_string.empty(), + get_logger(), !rt_buffer_.deactivate_controllers_list.empty(), "Deactivating following controllers as their hardware components read cycle resulted in an " "error: [ %s]", - stop_request_string.c_str()); + rt_buffer_.get_concatenated_string(rt_buffer_.deactivate_controllers_list).c_str()); std::vector & rt_controller_list = rt_controllers_wrapper_.update_and_get_used_by_rt_list(); - deactivate_controllers(rt_controller_list, stop_request); + deactivate_controllers(rt_controller_list, rt_buffer_.deactivate_controllers_list); // TODO(destogl): do auto-start of broadcasters } } @@ -2532,7 +2522,7 @@ controller_interface::return_type ControllerManager::update( "configuration (use_sim_time parameter) and if a valid clock source is available"); } - std::vector failed_controllers_list; + rt_buffer_.deactivate_controllers_list.clear(); for (const auto & loaded_controller : rt_controller_list) { // TODO(v-lopez) we could cache this information @@ -2630,21 +2620,18 @@ controller_interface::return_type ControllerManager::update( if (controller_ret != controller_interface::return_type::OK) { - failed_controllers_list.push_back(loaded_controller.info.name); + rt_buffer_.deactivate_controllers_list.push_back(loaded_controller.info.name); ret = controller_ret; } } } } - if (!failed_controllers_list.empty()) + if (!rt_buffer_.deactivate_controllers_list.empty()) { - const auto FALLBACK_STACK_MAX_SIZE = 500; - std::vector active_controllers_using_interfaces(failed_controllers_list); - active_controllers_using_interfaces.reserve(FALLBACK_STACK_MAX_SIZE); - std::vector cumulative_fallback_controllers; - cumulative_fallback_controllers.reserve(FALLBACK_STACK_MAX_SIZE); + rt_buffer_.fallback_controllers_list.clear(); + rt_buffer_.activate_controllers_using_interfaces_list.clear(); - for (const auto & failed_ctrl : failed_controllers_list) + for (const auto & failed_ctrl : rt_buffer_.deactivate_controllers_list) { auto ctrl_it = std::find_if( rt_controller_list.begin(), rt_controller_list.end(), @@ -2653,72 +2640,58 @@ controller_interface::return_type ControllerManager::update( { for (const auto & fallback_controller : ctrl_it->info.fallback_controllers_names) { - cumulative_fallback_controllers.push_back(fallback_controller); + rt_buffer_.fallback_controllers_list.push_back(fallback_controller); get_active_controllers_using_command_interfaces_of_controller( - fallback_controller, rt_controller_list, active_controllers_using_interfaces); + fallback_controller, rt_controller_list, + rt_buffer_.activate_controllers_using_interfaces_list); } } } - std::string controllers_string; - controllers_string.reserve(500); - for (const auto & controller : failed_controllers_list) - { - controllers_string.append(controller); - controllers_string.append(" "); - } + RCLCPP_ERROR( get_logger(), "Deactivating controllers : [ %s] as their update resulted in an error!", - controllers_string.c_str()); - if (active_controllers_using_interfaces.size() > failed_controllers_list.size()) - { - controllers_string.clear(); - for (size_t i = failed_controllers_list.size(); - i < active_controllers_using_interfaces.size(); i++) - { - controllers_string.append(active_controllers_using_interfaces[i]); - controllers_string.append(" "); - } - RCLCPP_ERROR_EXPRESSION( - get_logger(), !controllers_string.empty(), - "Deactivating controllers : [ %s] using the command interfaces needed for the fallback " - "controllers to activate.", - controllers_string.c_str()); - } - if (!cumulative_fallback_controllers.empty()) - { - controllers_string.clear(); - for (const auto & controller : cumulative_fallback_controllers) - { - controllers_string.append(controller); - controllers_string.append(" "); - } - RCLCPP_ERROR( - get_logger(), "Activating fallback controllers : [ %s]", controllers_string.c_str()); - } - std::vector failed_controller_interfaces, fallback_controller_interfaces; - failed_controller_interfaces.reserve(500); + rt_buffer_.get_concatenated_string(rt_buffer_.deactivate_controllers_list).c_str()); + RCLCPP_ERROR_EXPRESSION( + get_logger(), !rt_buffer_.activate_controllers_using_interfaces_list.empty(), + "Deactivating controllers : [ %s] using the command interfaces needed for the fallback " + "controllers to activate.", + rt_buffer_.get_concatenated_string(rt_buffer_.activate_controllers_using_interfaces_list) + .c_str()); + RCLCPP_ERROR_EXPRESSION( + get_logger(), !rt_buffer_.fallback_controllers_list.empty(), + "Activating fallback controllers : [ %s]", + rt_buffer_.get_concatenated_string(rt_buffer_.fallback_controllers_list).c_str()); + std::for_each( + rt_buffer_.activate_controllers_using_interfaces_list.begin(), + rt_buffer_.activate_controllers_using_interfaces_list.end(), + [this](const std::string & controller) + { add_element_to_list(rt_buffer_.deactivate_controllers_list, controller); }); + + // Retrieve the interfaces to start and stop from the hardware end + rt_buffer_.interfaces_to_start.clear(); + rt_buffer_.interfaces_to_stop.clear(); get_controller_list_command_interfaces( - failed_controllers_list, rt_controller_list, *resource_manager_, - failed_controller_interfaces); + rt_buffer_.deactivate_controllers_list, rt_controller_list, resource_manager_, + rt_buffer_.interfaces_to_stop); get_controller_list_command_interfaces( - cumulative_fallback_controllers, rt_controller_list, *resource_manager_, - fallback_controller_interfaces); - if (!failed_controller_interfaces.empty()) + rt_buffer_.fallback_controllers_list, rt_controller_list, resource_manager_, + rt_buffer_.interfaces_to_start); + if (!rt_buffer_.interfaces_to_stop.empty() || !rt_buffer_.interfaces_to_start.empty()) { if (!(resource_manager_->prepare_command_mode_switch( - fallback_controller_interfaces, failed_controller_interfaces) && + rt_buffer_.interfaces_to_start, rt_buffer_.interfaces_to_stop) && resource_manager_->perform_command_mode_switch( - fallback_controller_interfaces, failed_controller_interfaces))) + rt_buffer_.interfaces_to_start, rt_buffer_.interfaces_to_stop))) { RCLCPP_ERROR( get_logger(), "Error while attempting mode switch when deactivating controllers in update cycle!"); } } - deactivate_controllers(rt_controller_list, active_controllers_using_interfaces); - if (!cumulative_fallback_controllers.empty()) + deactivate_controllers(rt_controller_list, rt_buffer_.deactivate_controllers_list); + if (!rt_buffer_.fallback_controllers_list.empty()) { - activate_controllers(rt_controller_list, cumulative_fallback_controllers); + activate_controllers(rt_controller_list, rt_buffer_.fallback_controllers_list); } } @@ -2739,37 +2712,27 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration if (!ok) { - std::vector stop_request = {}; - std::string failed_hardware_string; - failed_hardware_string.reserve(500); + rt_buffer_.deactivate_controllers_list.clear(); // Determine controllers to stop for (const auto & hardware_name : failed_hardware_names) { - failed_hardware_string.append(hardware_name); - failed_hardware_string.append(" "); auto controllers = resource_manager_->get_cached_controllers_to_hardware(hardware_name); - stop_request.insert(stop_request.end(), controllers.begin(), controllers.end()); - } - std::string stop_request_string; - stop_request_string.reserve(500); - for (const auto & controller : stop_request) - { - stop_request_string.append(controller); - stop_request_string.append(" "); + rt_buffer_.deactivate_controllers_list.insert( + rt_buffer_.deactivate_controllers_list.end(), controllers.begin(), controllers.end()); } RCLCPP_ERROR( get_logger(), "Deactivating following hardware components as their write cycle resulted in an error: [ " "%s]", - failed_hardware_string.c_str()); + rt_buffer_.get_concatenated_string(failed_hardware_names).c_str()); RCLCPP_ERROR_EXPRESSION( - get_logger(), !stop_request_string.empty(), + get_logger(), !rt_buffer_.deactivate_controllers_list.empty(), "Deactivating following controllers as their hardware components write cycle resulted in an " "error: [ %s]", - stop_request_string.c_str()); + rt_buffer_.get_concatenated_string(rt_buffer_.deactivate_controllers_list).c_str()); std::vector & rt_controller_list = rt_controllers_wrapper_.update_and_get_used_by_rt_list(); - deactivate_controllers(rt_controller_list, stop_request); + deactivate_controllers(rt_controller_list, rt_buffer_.deactivate_controllers_list); // TODO(destogl): do auto-start of broadcasters } } From 45f871e261c22942ea7d685e03c6124bdbe27535 Mon Sep 17 00:00:00 2001 From: bijoua29 <73511637+bijoua29@users.noreply.github.com> Date: Mon, 17 Feb 2025 08:06:39 -0800 Subject: [PATCH 21/26] Fix unused timeouts in load/unload controller (#2052) --- controller_manager/controller_manager/spawner.py | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/controller_manager/controller_manager/spawner.py b/controller_manager/controller_manager/spawner.py index 58eb7be198..cbd8d6eaf9 100644 --- a/controller_manager/controller_manager/spawner.py +++ b/controller_manager/controller_manager/spawner.py @@ -229,7 +229,13 @@ def main(args=None): ): return 1 - ret = load_controller(node, controller_manager_name, controller_name) + ret = load_controller( + node, + controller_manager_name, + controller_name, + controller_manager_timeout, + service_call_timeout, + ) if not ret.ok: node.get_logger().fatal( bcolors.FAIL @@ -338,7 +344,13 @@ def main(args=None): unload_status = True for controller_name in controller_names: - ret = unload_controller(node, controller_manager_name, controller_name) + ret = unload_controller( + node, + controller_manager_name, + controller_name, + controller_manager_timeout, + service_call_timeout, + ) if not ret.ok: unload_status = False node.get_logger().error( From a9aca649d01c18d92307b9b3f6912c8fbd9159c7 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 18 Feb 2025 21:12:31 +0100 Subject: [PATCH 22/26] Add new `get_value` API for Handles and Interfaces (#1976) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --------- Co-authored-by: Dr. Denis Co-authored-by: Christoph Fröhlich --- .../force_torque_sensor.hpp | 4 +- .../semantic_components/imu_sensor.hpp | 8 +- .../semantic_components/pose_sensor.hpp | 4 +- .../semantic_components/range_sensor.hpp | 2 +- .../semantic_component_interface.hpp | 2 +- .../test_chainable_controller_interface.cpp | 13 +- .../test_chainable_controller.cpp | 10 +- .../test/test_controller/test_controller.cpp | 6 +- ...llers_chaining_with_controller_manager.cpp | 79 +- doc/migration.rst | 24 + doc/release_notes.rst | 1 + .../include/hardware_interface/handle.hpp | 63 +- .../loaned_command_interface.hpp | 72 +- .../loaned_state_interface.hpp | 55 +- .../mock_components/test_generic_system.cpp | 1012 ++++++++--------- .../test/test_component_interfaces.cpp | 264 +++-- ...est_component_interfaces_custom_export.cpp | 2 +- hardware_interface/test/test_handle.cpp | 25 +- .../test/test_resource_manager.cpp | 42 +- ...esource_manager_prepare_perform_switch.cpp | 240 ++-- 20 files changed, 1116 insertions(+), 812 deletions(-) diff --git a/controller_interface/include/semantic_components/force_torque_sensor.hpp b/controller_interface/include/semantic_components/force_torque_sensor.hpp index 18c3948962..d15a8f85b5 100644 --- a/controller_interface/include/semantic_components/force_torque_sensor.hpp +++ b/controller_interface/include/semantic_components/force_torque_sensor.hpp @@ -96,7 +96,7 @@ class ForceTorqueSensor : public SemanticComponentInterface().value(); ++interface_counter; } } @@ -123,7 +123,7 @@ class ForceTorqueSensor : public SemanticComponentInterface().value(); ++torque_interface_counter; } } diff --git a/controller_interface/include/semantic_components/imu_sensor.hpp b/controller_interface/include/semantic_components/imu_sensor.hpp index 793e5c0fea..675e85c760 100644 --- a/controller_interface/include/semantic_components/imu_sensor.hpp +++ b/controller_interface/include/semantic_components/imu_sensor.hpp @@ -52,7 +52,7 @@ class IMUSensor : public SemanticComponentInterface std::array orientation; for (auto i = 0u; i < orientation.size(); ++i) { - orientation[i] = state_interfaces_[i].get().get_value(); + orientation[i] = state_interfaces_[i].get().get_value().value(); } return orientation; } @@ -69,7 +69,8 @@ class IMUSensor : public SemanticComponentInterface const std::size_t interface_offset{4}; for (auto i = 0u; i < angular_velocity.size(); ++i) { - angular_velocity[i] = state_interfaces_[interface_offset + i].get().get_value(); + angular_velocity[i] = + state_interfaces_[interface_offset + i].get().get_value().value(); } return angular_velocity; } @@ -86,7 +87,8 @@ class IMUSensor : public SemanticComponentInterface const std::size_t interface_offset{7}; for (auto i = 0u; i < linear_acceleration.size(); ++i) { - linear_acceleration[i] = state_interfaces_[interface_offset + i].get().get_value(); + linear_acceleration[i] = + state_interfaces_[interface_offset + i].get().get_value().value(); } return linear_acceleration; } diff --git a/controller_interface/include/semantic_components/pose_sensor.hpp b/controller_interface/include/semantic_components/pose_sensor.hpp index 098fb04278..0192010bbb 100644 --- a/controller_interface/include/semantic_components/pose_sensor.hpp +++ b/controller_interface/include/semantic_components/pose_sensor.hpp @@ -50,7 +50,7 @@ class PoseSensor : public SemanticComponentInterface std::array position; for (auto i = 0u; i < position.size(); ++i) { - position[i] = state_interfaces_[i].get().get_value(); + position[i] = state_interfaces_[i].get().get_value().value(); } return position; } @@ -67,7 +67,7 @@ class PoseSensor : public SemanticComponentInterface const std::size_t interface_offset{3}; for (auto i = 0u; i < orientation.size(); ++i) { - orientation[i] = state_interfaces_[interface_offset + i].get().get_value(); + orientation[i] = state_interfaces_[interface_offset + i].get().get_value().value(); } return orientation; } diff --git a/controller_interface/include/semantic_components/range_sensor.hpp b/controller_interface/include/semantic_components/range_sensor.hpp index df4b0f46c5..464cef58e9 100644 --- a/controller_interface/include/semantic_components/range_sensor.hpp +++ b/controller_interface/include/semantic_components/range_sensor.hpp @@ -35,7 +35,7 @@ class RangeSensor : public SemanticComponentInterface * * \return value of the range in meters */ - float get_range() const { return state_interfaces_[0].get().get_value(); } + float get_range() const { return state_interfaces_[0].get().get_value().value(); } /// Return Range message with range in meters /** diff --git a/controller_interface/include/semantic_components/semantic_component_interface.hpp b/controller_interface/include/semantic_components/semantic_component_interface.hpp index 1f49e8cbff..63ea13418c 100644 --- a/controller_interface/include/semantic_components/semantic_component_interface.hpp +++ b/controller_interface/include/semantic_components/semantic_component_interface.hpp @@ -93,7 +93,7 @@ class SemanticComponentInterface // insert all the values for (auto i = 0u; i < state_interfaces_.size(); ++i) { - values.emplace_back(state_interfaces_[i].get().get_value()); + values.emplace_back(state_interfaces_[i].get().get_value().value()); } return true; } diff --git a/controller_interface/test/test_chainable_controller_interface.cpp b/controller_interface/test/test_chainable_controller_interface.cpp index 12d5599d45..9919ec3d60 100644 --- a/controller_interface/test/test_chainable_controller_interface.cpp +++ b/controller_interface/test/test_chainable_controller_interface.cpp @@ -52,7 +52,8 @@ TEST_F(ChainableControllerInterfaceTest, export_state_interfaces) EXPECT_EQ(exported_state_interfaces[0]->get_prefix_name(), TEST_CONTROLLER_NAME); EXPECT_EQ(exported_state_interfaces[0]->get_interface_name(), "test_state"); - EXPECT_EQ(exported_state_interfaces[0]->get_value(), EXPORTED_STATE_INTERFACE_VALUE); + EXPECT_EQ( + exported_state_interfaces[0]->get_value().value(), EXPORTED_STATE_INTERFACE_VALUE); } TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces) @@ -72,7 +73,7 @@ TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces) EXPECT_EQ(reference_interfaces[0]->get_prefix_name(), TEST_CONTROLLER_NAME); EXPECT_EQ(reference_interfaces[0]->get_interface_name(), "test_itf"); - EXPECT_EQ(reference_interfaces[0]->get_value(), INTERFACE_VALUE); + EXPECT_EQ(reference_interfaces[0]->get_value().value(), INTERFACE_VALUE); } TEST_F(ChainableControllerInterfaceTest, interfaces_prefix_is_not_node_name) @@ -120,7 +121,7 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode) EXPECT_FALSE(controller.is_in_chained_mode()); // Fail setting chained mode - EXPECT_EQ(reference_interfaces[0]->get_value(), INTERFACE_VALUE); + EXPECT_EQ(reference_interfaces[0]->get_value().value(), INTERFACE_VALUE); EXPECT_FALSE(controller.set_chained_mode(true)); EXPECT_FALSE(controller.is_in_chained_mode()); @@ -129,11 +130,13 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode) EXPECT_FALSE(controller.is_in_chained_mode()); // Success setting chained mode - reference_interfaces[0]->set_value(0.0); + (void)reference_interfaces[0]->set_value(0.0); EXPECT_TRUE(controller.set_chained_mode(true)); EXPECT_TRUE(controller.is_in_chained_mode()); - EXPECT_EQ(exported_state_interfaces[0]->get_value(), EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE); + EXPECT_EQ( + exported_state_interfaces[0]->get_value().value(), + EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE); controller.configure(); EXPECT_TRUE(controller.set_chained_mode(false)); diff --git a/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp b/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp index e68af6345f..644bda10cd 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp @@ -101,13 +101,15 @@ controller_interface::return_type TestChainableController::update_and_write_comm for (size_t i = 0; i < command_interfaces_.size(); ++i) { - command_interfaces_[i].set_value(reference_interfaces_[i] - state_interfaces_[i].get_value()); + (void)command_interfaces_[i].set_value( + reference_interfaces_[i] - state_interfaces_[i].get_value().value()); } // If there is a command interface then integrate and set it to the exported state interface data for (size_t i = 0; i < exported_state_interface_names_.size() && i < command_interfaces_.size(); ++i) { - state_interfaces_values_[i] = command_interfaces_[i].get_value() * CONTROLLER_DT; + state_interfaces_values_[i] = + command_interfaces_[i].get_value().value() * CONTROLLER_DT; } // If there is no command interface and if there is a state interface then just forward the same // value as in the state interface @@ -115,7 +117,7 @@ controller_interface::return_type TestChainableController::update_and_write_comm command_interfaces_.empty(); ++i) { - state_interfaces_values_[i] = state_interfaces_[i].get_value(); + state_interfaces_values_[i] = state_interfaces_[i].get_value().value(); } return controller_interface::return_type::OK; @@ -240,7 +242,7 @@ std::vector TestChainableController::get_state_interface_data() const std::vector state_intr_data; for (const auto & interface : state_interfaces_) { - state_intr_data.push_back(interface.get_value()); + state_intr_data.push_back(interface.get_value().value()); } return state_intr_data; } diff --git a/controller_manager/test/test_controller/test_controller.cpp b/controller_manager/test/test_controller/test_controller.cpp index 306799a66e..cadaf115ae 100644 --- a/controller_manager/test/test_controller/test_controller.cpp +++ b/controller_manager/test/test_controller/test_controller.cpp @@ -71,7 +71,7 @@ controller_interface::return_type TestController::update( // set value to hardware to produce and test different behaviors there if (!std::isnan(set_first_command_interface_value_to)) { - command_interfaces_[0].set_value(set_first_command_interface_value_to); + (void)command_interfaces_[0].set_value(set_first_command_interface_value_to); // reset to be easier to test set_first_command_interface_value_to = std::numeric_limits::quiet_NaN(); } @@ -90,7 +90,7 @@ controller_interface::return_type TestController::update( RCLCPP_DEBUG( get_node()->get_logger(), "Setting value of command interface '%s' to %f", command_interfaces_[i].get_name().c_str(), external_commands_for_testing_[i]); - command_interfaces_[i].set_value(external_commands_for_testing_[i]); + (void)command_interfaces_[i].set_value(external_commands_for_testing_[i]); } } @@ -187,7 +187,7 @@ std::vector TestController::get_state_interface_data() const std::vector state_intr_data; for (const auto & interface : state_interfaces_) { - state_intr_data.push_back(interface.get_value()); + state_intr_data.push_back(interface.get_value().value()); } return state_intr_data; } diff --git a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp index c143ab4862..059d3eecdf 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -520,8 +520,12 @@ class TestControllerChainingWithControllerManager // Command of DiffDrive controller are references of PID controllers EXP_LEFT_WHEEL_REF = chained_ctrl_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE); EXP_RIGHT_WHEEL_REF = chained_ctrl_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE); - ASSERT_EQ(diff_drive_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_REF); - ASSERT_EQ(diff_drive_controller->command_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_REF); + ASSERT_EQ( + diff_drive_controller->command_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_REF); + ASSERT_EQ( + diff_drive_controller->command_interfaces_[1].get_value().value(), + EXP_RIGHT_WHEEL_REF); ASSERT_EQ(pid_left_wheel_controller->reference_interfaces_[0], EXP_LEFT_WHEEL_REF); ASSERT_EQ(pid_right_wheel_controller->reference_interfaces_[0], EXP_RIGHT_WHEEL_REF); @@ -537,21 +541,32 @@ class TestControllerChainingWithControllerManager EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE); EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD); - ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD); - ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + ASSERT_EQ( + pid_left_wheel_controller->command_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_CMD); + ASSERT_EQ( + pid_left_wheel_controller->state_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_HW_STATE); // DiffDrive uses the same state - ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + ASSERT_EQ( + diff_drive_controller->state_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_HW_STATE); // The state doesn't change wrt to any data from the hardware calculation ASSERT_EQ(robot_localization_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE); EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD); - ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD); ASSERT_EQ( - pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + pid_right_wheel_controller->command_interfaces_[0].get_value().value(), + EXP_RIGHT_WHEEL_CMD); + ASSERT_EQ( + pid_right_wheel_controller->state_interfaces_[0].get_value().value(), + EXP_RIGHT_WHEEL_HW_STATE); // DiffDrive uses the same state - ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + ASSERT_EQ( + diff_drive_controller->state_interfaces_[1].get_value().value(), + EXP_RIGHT_WHEEL_HW_STATE); // The state doesn't change wrt to any data from the hardware calculation ASSERT_EQ(robot_localization_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); @@ -811,10 +826,16 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE); // 32 / 2 EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD); - ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD); - ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + ASSERT_EQ( + pid_left_wheel_controller->command_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_CMD); + ASSERT_EQ( + pid_left_wheel_controller->state_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_HW_STATE); // DiffDrive uses the same state - ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + ASSERT_EQ( + diff_drive_controller->state_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_HW_STATE); // The state doesn't change wrt to any data from the hardware calculation ASSERT_EQ(robot_localization_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); @@ -823,13 +844,19 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE); // 128 / 2 EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD); - ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD); - ASSERT_EQ(pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + ASSERT_EQ( + pid_right_wheel_controller->command_interfaces_[0].get_value().value(), + EXP_RIGHT_WHEEL_CMD); + ASSERT_EQ( + pid_right_wheel_controller->state_interfaces_[0].get_value().value(), + EXP_RIGHT_WHEEL_HW_STATE); ASSERT_EQ(odom_publisher_controller->internal_counter, 2u); ASSERT_EQ(sensor_fusion_controller->internal_counter, 6u); ASSERT_EQ(robot_localization_controller->internal_counter, 4u); // DiffDrive uses the same state - ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + ASSERT_EQ( + diff_drive_controller->state_interfaces_[1].get_value().value(), + EXP_RIGHT_WHEEL_HW_STATE); // The state doesn't change wrt to any data from the hardware calculation ASSERT_EQ(robot_localization_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); @@ -1986,19 +2013,31 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE); // 32 / 2 EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD); - ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD); - ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + ASSERT_EQ( + pid_left_wheel_controller->command_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_CMD); + ASSERT_EQ( + pid_left_wheel_controller->state_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_HW_STATE); // DiffDrive uses the same state - ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + ASSERT_EQ( + diff_drive_controller->state_interfaces_[0].get_value().value(), + EXP_LEFT_WHEEL_HW_STATE); // 128 - 0 EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE); // 128 / 2 EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD); - ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD); - ASSERT_EQ(pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + ASSERT_EQ( + pid_right_wheel_controller->command_interfaces_[0].get_value().value(), + EXP_RIGHT_WHEEL_CMD); + ASSERT_EQ( + pid_right_wheel_controller->state_interfaces_[0].get_value().value(), + EXP_RIGHT_WHEEL_HW_STATE); // DiffDrive uses the same state - ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + ASSERT_EQ( + diff_drive_controller->state_interfaces_[1].get_value().value(), + EXP_RIGHT_WHEEL_HW_STATE); // update all controllers at once and see that all have expected values --> also checks the order // of controller execution diff --git a/doc/migration.rst b/doc/migration.rst index 9e91768bc6..777f724cee 100644 --- a/doc/migration.rst +++ b/doc/migration.rst @@ -75,12 +75,36 @@ hardware_interface ****************** * ``test_components`` was moved to its own package. Update the dependencies if you are using them. (`#1325 `_) * With (`#1683 `_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 `_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles. +* A new ``get_value`` that returns a ``std::optional`` was added to the ``CommandInterface`` and ``StateInterface``. This can be used to check if the value is available or not. (`#1976 `_) Adaption of Command-/StateInterfaces *************************************** +* The handles for ``Command-/StateInterfaces`` have new set/get methods to access the values. * ``Command-/StateInterfaces`` are now created and exported automatically by the framework via the ``on_export_command_interfaces()`` or ``on_export_state_interfaces()`` methods based on the interfaces defined in the ``ros2_control`` XML-tag, which get parsed and the ``InterfaceDescription`` is created accordingly (check the `hardware_info.hpp `__). The memory is now allocated in the handle itself. +Access to Command-/StateInterfaces +---------------------------------- + +Earlier code will issue compile-time warnings like: + +.. code:: + + warning: ‘double hardware_interface::Handle::get_value() const’ is deprecated: Use std::optional get_value() or bool get_value(double & value) instead to retrieve the value. [-Wdeprecated-declarations] + warning: ignoring return value of ‘bool hardware_interface::Handle::set_value(const T&) [with T = double]’ [-Wunused-result] + +The old methods are deprecated and will be removed in the future. The new methods are: + + * ``std::optional get_value()`` or ``bool get_value(T & value)`` for getting the value. + * ``bool set_value(const T & value)`` for setting the value. + +The return value ``bool`` or ``std::optional`` with ``get_value`` can be used to check if the value is available or not. Similarly, the ``set_value`` method returns a ``bool`` to check if the value was set or not. +The ``get_value`` method will return an empty ``std::nullopt`` or ``false`` if the value is not available. The ``set_value`` method will return ``false`` if the value was not set. + +.. note:: + Checking the result of these operations is important as the value might not be available or the value might not be set. + This is usually the case when the ros2_control framework has some asynchronous operations due to asynchronous controllers or asynchronous hardware components where different threads are involved to access the same data. + Migration of Command-/StateInterfaces ------------------------------------- To adapt to the new way of creating and exporting ``Command-/StateInterfaces`` follow those steps: diff --git a/doc/release_notes.rst b/doc/release_notes.rst index efe81d0567..9143dc6ac1 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -164,6 +164,7 @@ hardware_interface * With (`#1763 `_) parsing for SDF published to ``robot_description`` topic is now also supported. * With (`#1567 `_) all the Hardware components now have a fully functional asynchronous functionality, by simply adding ``is_async`` tag to the ros2_control tag in the URDF. This will allow the hardware components to run in a separate thread, and the controller manager will be able to run the controllers in parallel with the hardware components. * The hardware components can be easily introspect the internal member variables using the macro ``REGISTER_ROS2_CONTROL_INTROSPECTION`` (`#1918 `_) +* Added new ``get_value`` method that returns ``std::optional`` of the templated type, and this can be used to check if the value is available or not (`#1976 `_) joint_limits ************ diff --git a/hardware_interface/include/hardware_interface/handle.hpp b/hardware_interface/include/hardware_interface/handle.hpp index ddb9dbd99c..53a0e1ee3a 100644 --- a/hardware_interface/include/hardware_interface/handle.hpp +++ b/hardware_interface/include/hardware_interface/handle.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -111,7 +112,9 @@ class Handle const std::string & get_prefix_name() const { return prefix_name_; } - [[deprecated("Use bool get_value(double & value) instead to retrieve the value.")]] + [[deprecated( + "Use std::optional get_value() or bool get_value(double & " + "value) instead to retrieve the value.")]] double get_value() const { std::shared_lock lock(handle_mutex_, std::try_to_lock); @@ -126,7 +129,44 @@ class Handle // END } - [[nodiscard]] bool get_value(double & value) const + /** + * @brief Get the value of the handle. + * @tparam T The type of the value to be retrieved. + * @return The value of the handle if it accessed successfully, std::nullopt otherwise. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the same handle at same instance, and if they are unable to + * lock the handle to access the value, the handle returns std::nullopt. If the operation is + * successful, the value is returned. + */ + template + [[nodiscard]] std::optional get_value() const + { + std::shared_lock lock(handle_mutex_, std::try_to_lock); + if (!lock.owns_lock()) + { + return std::nullopt; + } + THROW_ON_NULLPTR(this->value_ptr_); + // BEGIN (Handle export change): for backward compatibility + // TODO(saikishor) return value_ if old functionality is removed + return value_ptr_ != nullptr ? *value_ptr_ : std::get(value_); + // END + } + + /** + * @brief Get the value of the handle. + * @tparam T The type of the value to be retrieved. + * @param value The value of the handle. + * @return true if the value is accessed successfully, false otherwise. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the same handle at same instance, and if they are unable to + * lock the handle to access the value, the handle returns false. If the operation is successful, + * the value is updated and returns true. + */ + template + [[nodiscard]] bool get_value(T & value) const { std::shared_lock lock(handle_mutex_, std::try_to_lock); if (!lock.owns_lock()) @@ -134,14 +174,25 @@ class Handle return false; } // BEGIN (Handle export change): for backward compatibility - // TODO(Manuel) set value directly if old functionality is removed - THROW_ON_NULLPTR(value_ptr_); - value = *value_ptr_; + // TODO(Manuel) return value_ if old functionality is removed + value = value_ptr_ != nullptr ? *value_ptr_ : std::get(value_); return true; // END } - [[nodiscard]] bool set_value(double value) + /** + * @brief Set the value of the handle. + * @tparam T The type of the value to be set. + * @param value The value to be set. + * @return true if the value is set successfully, false otherwise. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the same handle at same instance, and if they are unable to + * lock the handle to set the value, the handle returns false. If the operation is successful, the + * handle is updated and returns true. + */ + template + [[nodiscard]] bool set_value(const T & value) { std::unique_lock lock(handle_mutex_, std::try_to_lock); if (!lock.owns_lock()) diff --git a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp index 7bb4d3a0ef..3e4c0ca441 100644 --- a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp @@ -94,8 +94,23 @@ class LoanedCommandInterface const std::string & get_prefix_name() const { return command_interface_.get_prefix_name(); } + /** + * @brief Set the value of the command interface. + * @tparam T The type of the value to be set. + * @param value The value to set. + * @param max_tries The maximum number of tries to set the value. + * @return true if the value is set successfully, false otherwise. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the internal handle at same instance, and if they are + * unable to lock the handle to set the value, the handle returns false. If the operation is + * successful, the handle is updated and returns true. + * @note The method will try to set the value max_tries times before returning false. The method + * will yield the thread between tries. If the value is set successfully, the method returns true + * immediately. + */ template - [[nodiscard]] bool set_value(T value, unsigned int max_tries = 10) + [[nodiscard]] bool set_value(const T & value, unsigned int max_tries = 10) { unsigned int nr_tries = 0; ++set_value_statistics_.total_counter; @@ -113,9 +128,12 @@ class LoanedCommandInterface return true; } + [[deprecated( + "Use std::optional get_value() or bool get_value(double & " + "value) instead to retrieve the value.")]] double get_value() const { - double value; + double value = std::numeric_limits::quiet_NaN(); if (get_value(value)) { return value; @@ -126,6 +144,56 @@ class LoanedCommandInterface } } + /** + * @brief Get the value of the command interface. + * @tparam T The type of the value to be retrieved. + * @return The value of the command interface if it accessed successfully, std::nullopt otherwise. + * @param max_tries The maximum number of tries to get the value. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the internal handle at same instance, and if they are + * unable to lock the handle to access the value, the handle returns std::nullopt. If the + * operation is successful, the value is returned. + * @note The method will try to get the value max_tries times before returning std::nullopt. The + * method will yield the thread between tries. If the value is retrieved successfully, the method + * returns the value immediately. + */ + template + [[nodiscard]] std::optional get_value(unsigned int max_tries = 10) const + { + unsigned int nr_tries = 0; + do + { + ++get_value_statistics_.total_counter; + const std::optional data = command_interface_.get_value(); + if (data.has_value()) + { + return data; + } + ++get_value_statistics_.failed_counter; + ++nr_tries; + std::this_thread::yield(); + } while (nr_tries < max_tries); + + ++get_value_statistics_.timeout_counter; + return std::nullopt; + } + + /** + * @brief Get the value of the command interface. + * @tparam T The type of the value to be retrieved. + * @param value The value of the command interface. + * @param max_tries The maximum number of tries to get the value. + * @return true if the value is accessed successfully, false otherwise. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the internal handle at same instance, and if they are + * unable to lock the handle to access the value, the handle returns false. If the operation is + * successful, the value is updated and returns true. + * @note The method will try to get the value max_tries times before returning false. The method + * will yield the thread between tries. If the value is updated successfully, the method returns + * true immediately. + */ template [[nodiscard]] bool get_value(T & value, unsigned int max_tries = 10) const { diff --git a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp index 27b3da813e..cb7b99066a 100644 --- a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp @@ -88,9 +88,12 @@ class LoanedStateInterface const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); } + [[deprecated( + "Use std::optional get_value() or bool get_value(double & " + "value) instead to retrieve the value.")]] double get_value() const { - double value; + double value = std::numeric_limits::quiet_NaN(); if (get_value(value)) { return value; @@ -101,6 +104,56 @@ class LoanedStateInterface } } + /** + * @brief Get the value of the state interface. + * @tparam T The type of the value to be retrieved. + * @return The value of the state interface if it accessed successfully, std::nullopt otherwise. + * @param max_tries The maximum number of tries to get the value. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the internal handle at same instance, and if they are + * unable to lock the handle to access the value, the handle returns std::nullopt. If the + * operation is successful, the value is returned. + * @note The method will try to get the value max_tries times before returning std::nullopt. The + * method will yield the thread between tries. If the value is retrieved successfully, the method + * returns the value immediately. + */ + template + [[nodiscard]] std::optional get_value(unsigned int max_tries = 10) const + { + unsigned int nr_tries = 0; + do + { + ++get_value_statistics_.total_counter; + const std::optional data = state_interface_.get_value(); + if (data.has_value()) + { + return data; + } + ++get_value_statistics_.failed_counter; + ++nr_tries; + std::this_thread::yield(); + } while (nr_tries < max_tries); + + ++get_value_statistics_.timeout_counter; + return std::nullopt; + } + + /** + * @brief Get the value of the state interface. + * @tparam T The type of the value to be retrieved. + * @param value The value of the state interface. + * @param max_tries The maximum number of tries to get the value. + * @return true if the value is accessed successfully, false otherwise. + * + * @note The method is thread-safe and non-blocking. + * @note When different threads access the same handle at same instance, and if they are unable to + * lock the handle to access the value, the handle returns false. If the operation is successful, + * the value is updated and returns true. + * @note The method will try to get the value max_tries times before returning false. The method + * will yield the thread between tries. If the value is retrieved successfully, the method updates + * the value and returns true immediately. + */ template [[nodiscard]] bool get_value(T & value, unsigned int max_tries = 10) const { diff --git a/hardware_interface/test/mock_components/test_generic_system.cpp b/hardware_interface/test/mock_components/test_generic_system.cpp index 446634d12f..815647b3f5 100644 --- a/hardware_interface/test/mock_components/test_generic_system.cpp +++ b/hardware_interface/test/mock_components/test_generic_system.cpp @@ -778,10 +778,10 @@ TEST_F(TestGenericSystem, generic_system_2dof_symetric_interfaces) hardware_interface::LoanedCommandInterface j1p_c = rm.claim_command_interface("joint1/position"); hardware_interface::LoanedCommandInterface j2p_c = rm.claim_command_interface("joint2/position"); - ASSERT_EQ(1.57, j1p_s.get_value()); - ASSERT_EQ(0.7854, j2p_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); + ASSERT_EQ(1.57, j1p_s.get_value().value()); + ASSERT_EQ(0.7854, j2p_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); } // Test inspired by hardware_interface/test_resource_manager.cpp @@ -827,10 +827,10 @@ TEST_F(TestGenericSystem, generic_system_2dof_asymetric_interfaces) hardware_interface::LoanedCommandInterface j2a_c = rm.claim_command_interface("joint2/acceleration"); - ASSERT_EQ(1.57, j1v_s.get_value()); - ASSERT_EQ(0.7854, j2p_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j2a_c.get_value())); + ASSERT_EQ(1.57, j1v_s.get_value().value()); + ASSERT_EQ(0.7854, j2p_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2a_c.get_value().value())); } void generic_system_functional_test( @@ -867,68 +867,68 @@ void generic_system_functional_test( hardware_interface::LoanedCommandInterface j2v_c = rm.claim_command_interface("joint2/velocity"); // State interfaces without initial value are set to 0 - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j1v_c.set_value(0.22); - j2p_c.set_value(0.33); - j2v_c.set_value(0.44); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j1v_c.set_value(0.22)); + ASSERT_TRUE(j2p_c.set_value(0.33)); + ASSERT_TRUE(j2v_c.set_value(0.44)); // State values should not be changed - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // write() does not change values ASSERT_TRUE(rm.write(TIME, PERIOD).ok); - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // read() mirrors commands + offset to states ASSERT_TRUE(rm.read(TIME, PERIOD).ok); - ASSERT_EQ(0.11 + offset, j1p_s.get_value()); - ASSERT_EQ(0.22, j1v_s.get_value()); - ASSERT_EQ(0.33 + offset, j2p_s.get_value()); - ASSERT_EQ(0.44, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(0.11 + offset, j1p_s.get_value().value()); + ASSERT_EQ(0.22, j1v_s.get_value().value()); + ASSERT_EQ(0.33 + offset, j2p_s.get_value().value()); + ASSERT_EQ(0.44, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // set some new values in commands - j1p_c.set_value(0.55); - j1v_c.set_value(0.66); - j2p_c.set_value(0.77); - j2v_c.set_value(0.88); + ASSERT_TRUE(j1p_c.set_value(0.55)); + ASSERT_TRUE(j1v_c.set_value(0.66)); + ASSERT_TRUE(j2p_c.set_value(0.77)); + ASSERT_TRUE(j2v_c.set_value(0.88)); // state values should not be changed - ASSERT_EQ(0.11 + offset, j1p_s.get_value()); - ASSERT_EQ(0.22, j1v_s.get_value()); - ASSERT_EQ(0.33 + offset, j2p_s.get_value()); - ASSERT_EQ(0.44, j2v_s.get_value()); - ASSERT_EQ(0.55, j1p_c.get_value()); - ASSERT_EQ(0.66, j1v_c.get_value()); - ASSERT_EQ(0.77, j2p_c.get_value()); - ASSERT_EQ(0.88, j2v_c.get_value()); + ASSERT_EQ(0.11 + offset, j1p_s.get_value().value()); + ASSERT_EQ(0.22, j1v_s.get_value().value()); + ASSERT_EQ(0.33 + offset, j2p_s.get_value().value()); + ASSERT_EQ(0.44, j2v_s.get_value().value()); + ASSERT_EQ(0.55, j1p_c.get_value().value()); + ASSERT_EQ(0.66, j1v_c.get_value().value()); + ASSERT_EQ(0.77, j2p_c.get_value().value()); + ASSERT_EQ(0.88, j2v_c.get_value().value()); deactivate_components(rm, {component_name}); status_map = rm.get_components_status(); @@ -973,72 +973,72 @@ void generic_system_error_group_test( hardware_interface::LoanedCommandInterface j2v_c = rm.claim_command_interface("joint2/velocity"); // State interfaces without initial value are set to 0 - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j1v_c.set_value(0.22); - j2p_c.set_value(0.33); - j2v_c.set_value(0.44); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j1v_c.set_value(0.22)); + ASSERT_TRUE(j2p_c.set_value(0.33)); + ASSERT_TRUE(j2v_c.set_value(0.44)); // State values should not be changed - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // write() does not change values ASSERT_TRUE(rm.write(TIME, PERIOD).ok); - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // read() mirrors commands to states ASSERT_TRUE(rm.read(TIME, PERIOD).ok); - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.22, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - ASSERT_EQ(0.44, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.22, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + ASSERT_EQ(0.44, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // set some new values in commands - j1p_c.set_value(0.55); - j1v_c.set_value(0.66); - j2p_c.set_value(0.77); - j2v_c.set_value(0.88); + ASSERT_TRUE(j1p_c.set_value(0.55)); + ASSERT_TRUE(j1v_c.set_value(0.66)); + ASSERT_TRUE(j2p_c.set_value(0.77)); + ASSERT_TRUE(j2v_c.set_value(0.88)); // state values should not be changed - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.22, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - ASSERT_EQ(0.44, j2v_s.get_value()); - ASSERT_EQ(0.55, j1p_c.get_value()); - ASSERT_EQ(0.66, j1v_c.get_value()); - ASSERT_EQ(0.77, j2p_c.get_value()); - ASSERT_EQ(0.88, j2v_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.22, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + ASSERT_EQ(0.44, j2v_s.get_value().value()); + ASSERT_EQ(0.55, j1p_c.get_value().value()); + ASSERT_EQ(0.66, j1v_c.get_value().value()); + ASSERT_EQ(0.77, j2p_c.get_value().value()); + ASSERT_EQ(0.88, j2v_c.get_value().value()); // Error testing - j1p_c.set_value(std::numeric_limits::infinity()); - j1v_c.set_value(std::numeric_limits::infinity()); + ASSERT_TRUE(j1p_c.set_value(std::numeric_limits::infinity())); + ASSERT_TRUE(j1v_c.set_value(std::numeric_limits::infinity())); // read() should now bring error in the first component auto read_result = rm.read(TIME, PERIOD); ASSERT_FALSE(read_result.ok); @@ -1075,8 +1075,8 @@ void generic_system_error_group_test( } // Error should be recoverable only after reactivating the hardware component - j1p_c.set_value(0.0); - j1v_c.set_value(0.0); + ASSERT_TRUE(j1p_c.set_value(0.0)); + ASSERT_TRUE(j1v_c.set_value(0.0)); ASSERT_FALSE(rm.read(TIME, PERIOD).ok); // Now it should be recoverable @@ -1154,51 +1154,51 @@ TEST_F(TestGenericSystem, generic_system_2dof_other_interfaces) hardware_interface::LoanedCommandInterface vo_c = rm.claim_command_interface("voltage_output/voltage"); - ASSERT_EQ(1.55, j1p_s.get_value()); - ASSERT_EQ(0.1, j1v_s.get_value()); - ASSERT_EQ(0.65, j2p_s.get_value()); - ASSERT_EQ(0.2, j2v_s.get_value()); - ASSERT_EQ(0.5, vo_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); - ASSERT_TRUE(std::isnan(vo_c.get_value())); + ASSERT_EQ(1.55, j1p_s.get_value().value()); + ASSERT_EQ(0.1, j1v_s.get_value().value()); + ASSERT_EQ(0.65, j2p_s.get_value().value()); + ASSERT_EQ(0.2, j2v_s.get_value().value()); + ASSERT_EQ(0.5, vo_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); + ASSERT_TRUE(std::isnan(vo_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j2p_c.set_value(0.33); - vo_c.set_value(0.99); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j2p_c.set_value(0.33)); + ASSERT_TRUE(vo_c.set_value(0.99)); // State values should not be changed - ASSERT_EQ(1.55, j1p_s.get_value()); - ASSERT_EQ(0.1, j1v_s.get_value()); - ASSERT_EQ(0.65, j2p_s.get_value()); - ASSERT_EQ(0.2, j2v_s.get_value()); - ASSERT_EQ(0.5, vo_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.99, vo_c.get_value()); + ASSERT_EQ(1.55, j1p_s.get_value().value()); + ASSERT_EQ(0.1, j1v_s.get_value().value()); + ASSERT_EQ(0.65, j2p_s.get_value().value()); + ASSERT_EQ(0.2, j2v_s.get_value().value()); + ASSERT_EQ(0.5, vo_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.99, vo_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_EQ(1.55, j1p_s.get_value()); - ASSERT_EQ(0.1, j1v_s.get_value()); - ASSERT_EQ(0.65, j2p_s.get_value()); - ASSERT_EQ(0.2, j2v_s.get_value()); - ASSERT_EQ(0.5, vo_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.99, vo_c.get_value()); + ASSERT_EQ(1.55, j1p_s.get_value().value()); + ASSERT_EQ(0.1, j1v_s.get_value().value()); + ASSERT_EQ(0.65, j2p_s.get_value().value()); + ASSERT_EQ(0.2, j2v_s.get_value().value()); + ASSERT_EQ(0.5, vo_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.99, vo_c.get_value().value()); // read() mirrors commands to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.1, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - ASSERT_EQ(0.99, vo_s.get_value()); - ASSERT_EQ(0.2, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.99, vo_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.1, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + ASSERT_EQ(0.99, vo_s.get_value().value()); + ASSERT_EQ(0.2, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.99, vo_c.get_value().value()); } TEST_F(TestGenericSystem, generic_system_2dof_sensor) @@ -1247,58 +1247,58 @@ TEST_F(TestGenericSystem, generic_system_2dof_sensor) EXPECT_ANY_THROW(rm.claim_command_interface("tcp_force_sensor/tx")); EXPECT_ANY_THROW(rm.claim_command_interface("tcp_force_sensor/ty")); - ASSERT_EQ(0.0, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); + ASSERT_EQ(0.0, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j2p_c.set_value(0.33); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j2p_c.set_value(0.33)); // State values should not be changed - ASSERT_EQ(0.0, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); + ASSERT_EQ(0.0, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_EQ(0.0, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); + ASSERT_EQ(0.0, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); // read() mirrors commands to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); } void TestGenericSystem::test_generic_system_with_mock_sensor_commands( @@ -1350,78 +1350,78 @@ void TestGenericSystem::test_generic_system_with_mock_sensor_commands( hardware_interface::LoanedCommandInterface sty_c = rm.claim_command_interface("tcp_force_sensor/ty"); - ASSERT_EQ(0.0, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); - EXPECT_TRUE(std::isnan(sfx_c.get_value())); - EXPECT_TRUE(std::isnan(sfy_c.get_value())); - EXPECT_TRUE(std::isnan(stx_c.get_value())); - EXPECT_TRUE(std::isnan(sty_c.get_value())); + ASSERT_EQ(0.0, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); + EXPECT_TRUE(std::isnan(sfx_c.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_c.get_value().value())); + EXPECT_TRUE(std::isnan(stx_c.get_value().value())); + EXPECT_TRUE(std::isnan(sty_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j2p_c.set_value(0.33); - sfx_c.set_value(1.11); - sfy_c.set_value(2.22); - stx_c.set_value(3.33); - sty_c.set_value(4.44); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j2p_c.set_value(0.33)); + ASSERT_TRUE(sfx_c.set_value(1.11)); + ASSERT_TRUE(sfy_c.set_value(2.22)); + ASSERT_TRUE(stx_c.set_value(3.33)); + ASSERT_TRUE(sty_c.set_value(4.44)); // State values should not be changed - ASSERT_EQ(0.0, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(1.11, sfx_c.get_value()); - ASSERT_EQ(2.22, sfy_c.get_value()); - ASSERT_EQ(3.33, stx_c.get_value()); - ASSERT_EQ(4.44, sty_c.get_value()); + ASSERT_EQ(0.0, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(1.11, sfx_c.get_value().value()); + ASSERT_EQ(2.22, sfy_c.get_value().value()); + ASSERT_EQ(3.33, stx_c.get_value().value()); + ASSERT_EQ(4.44, sty_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_EQ(0.0, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - EXPECT_TRUE(std::isnan(sfx_s.get_value())); - EXPECT_TRUE(std::isnan(sfy_s.get_value())); - EXPECT_TRUE(std::isnan(stx_s.get_value())); - EXPECT_TRUE(std::isnan(sty_s.get_value())); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(1.11, sfx_c.get_value()); - ASSERT_EQ(2.22, sfy_c.get_value()); - ASSERT_EQ(3.33, stx_c.get_value()); - ASSERT_EQ(4.44, sty_c.get_value()); + ASSERT_EQ(0.0, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_TRUE(std::isnan(sfx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sfy_s.get_value().value())); + EXPECT_TRUE(std::isnan(stx_s.get_value().value())); + EXPECT_TRUE(std::isnan(sty_s.get_value().value())); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(1.11, sfx_c.get_value().value()); + ASSERT_EQ(2.22, sfy_c.get_value().value()); + ASSERT_EQ(3.33, stx_c.get_value().value()); + ASSERT_EQ(4.44, sty_c.get_value().value()); // read() mirrors commands to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(1.11, sfx_s.get_value()); - ASSERT_EQ(2.22, sfy_s.get_value()); - ASSERT_EQ(3.33, stx_s.get_value()); - ASSERT_EQ(4.44, sty_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(1.11, sfx_c.get_value()); - ASSERT_EQ(2.22, sfy_c.get_value()); - ASSERT_EQ(3.33, stx_c.get_value()); - ASSERT_EQ(4.44, sty_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(1.11, sfx_s.get_value().value()); + ASSERT_EQ(2.22, sfy_s.get_value().value()); + ASSERT_EQ(3.33, stx_s.get_value().value()); + ASSERT_EQ(4.44, sty_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(1.11, sfx_c.get_value().value()); + ASSERT_EQ(2.22, sfy_c.get_value().value()); + ASSERT_EQ(3.33, stx_c.get_value().value()); + ASSERT_EQ(4.44, sty_c.get_value().value()); } TEST_F(TestGenericSystem, generic_system_2dof_sensor_mock_command) @@ -1468,42 +1468,42 @@ void TestGenericSystem::test_generic_system_with_mimic_joint( hardware_interface::LoanedCommandInterface j1p_c = rm.claim_command_interface("joint1/position"); hardware_interface::LoanedCommandInterface j1v_c = rm.claim_command_interface("joint1/velocity"); - ASSERT_EQ(1.57, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); + ASSERT_EQ(1.57, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j1v_c.set_value(0.05); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j1v_c.set_value(0.05)); // State values should not be changed - ASSERT_EQ(1.57, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.05, j1v_c.get_value()); + ASSERT_EQ(1.57, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.05, j1v_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_EQ(1.57, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.0, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.05, j1v_c.get_value()); + ASSERT_EQ(1.57, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.0, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.05, j1v_c.get_value().value()); // read() mirrors commands to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.05, j1v_s.get_value()); - ASSERT_EQ(-0.22, j2p_s.get_value()); - ASSERT_EQ(-0.1, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.05, j1v_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.05, j1v_s.get_value().value()); + ASSERT_EQ(-0.22, j2p_s.get_value().value()); + ASSERT_EQ(-0.1, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.05, j1v_c.get_value().value()); } TEST_F(TestGenericSystem, hardware_system_2dof_with_mimic_joint) @@ -1577,72 +1577,72 @@ TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset_custom_i rm.claim_state_interface("joint2/actual_position"); // State interfaces without initial value are set to 0 - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2p_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); - j1v_c.set_value(0.22); - j2p_c.set_value(0.33); - j2v_c.set_value(0.44); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j1v_c.set_value(0.22)); + ASSERT_TRUE(j2p_c.set_value(0.33)); + ASSERT_TRUE(j2v_c.set_value(0.44)); // State values should not be changed - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(2.78, j2p_s.get_value()); - ASSERT_EQ(0.0, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(2.78, j2p_s.get_value().value()); + ASSERT_EQ(0.0, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // read() mirrors commands + offset to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.11 + offset, c_j1p_s.get_value()); - ASSERT_EQ(0.22, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - ASSERT_EQ(0.33 + offset, c_j2p_s.get_value()); - ASSERT_EQ(0.44, j2v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.22, j1v_c.get_value()); - ASSERT_EQ(0.33, j2p_c.get_value()); - ASSERT_EQ(0.44, j2v_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.11 + offset, c_j1p_s.get_value().value()); + ASSERT_EQ(0.22, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + ASSERT_EQ(0.33 + offset, c_j2p_s.get_value().value()); + ASSERT_EQ(0.44, j2v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.22, j1v_c.get_value().value()); + ASSERT_EQ(0.33, j2p_c.get_value().value()); + ASSERT_EQ(0.44, j2v_c.get_value().value()); // set some new values in commands - j1p_c.set_value(0.55); - j1v_c.set_value(0.66); - j2p_c.set_value(0.77); - j2v_c.set_value(0.88); + ASSERT_TRUE(j1p_c.set_value(0.55)); + ASSERT_TRUE(j1v_c.set_value(0.66)); + ASSERT_TRUE(j2p_c.set_value(0.77)); + ASSERT_TRUE(j2v_c.set_value(0.88)); // state values should not be changed - ASSERT_EQ(0.11, j1p_s.get_value()); - ASSERT_EQ(0.11 + offset, c_j1p_s.get_value()); - ASSERT_EQ(0.22, j1v_s.get_value()); - ASSERT_EQ(0.33, j2p_s.get_value()); - ASSERT_EQ(0.33 + offset, c_j2p_s.get_value()); - ASSERT_EQ(0.44, j2v_s.get_value()); - ASSERT_EQ(0.55, j1p_c.get_value()); - ASSERT_EQ(0.66, j1v_c.get_value()); - ASSERT_EQ(0.77, j2p_c.get_value()); - ASSERT_EQ(0.88, j2v_c.get_value()); + ASSERT_EQ(0.11, j1p_s.get_value().value()); + ASSERT_EQ(0.11 + offset, c_j1p_s.get_value().value()); + ASSERT_EQ(0.22, j1v_s.get_value().value()); + ASSERT_EQ(0.33, j2p_s.get_value().value()); + ASSERT_EQ(0.33 + offset, c_j2p_s.get_value().value()); + ASSERT_EQ(0.44, j2v_s.get_value().value()); + ASSERT_EQ(0.55, j1p_c.get_value().value()); + ASSERT_EQ(0.66, j1v_c.get_value().value()); + ASSERT_EQ(0.77, j2p_c.get_value().value()); + ASSERT_EQ(0.88, j2v_c.get_value().value()); deactivate_components(rm, {hardware_name}); status_map = rm.get_components_status(); @@ -1705,44 +1705,44 @@ TEST_F(TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio) rm.claim_command_interface("flange_vacuum/vacuum"); // State interfaces without initial value are set to 0 - ASSERT_TRUE(std::isnan(gpio1_a_o1_s.get_value())); - ASSERT_TRUE(std::isnan(gpio2_vac_s.get_value())); - ASSERT_TRUE(std::isnan(gpio1_a_o1_c.get_value())); - ASSERT_TRUE(std::isnan(gpio2_vac_c.get_value())); + ASSERT_TRUE(std::isnan(gpio1_a_o1_s.get_value().value())); + ASSERT_TRUE(std::isnan(gpio2_vac_s.get_value().value())); + ASSERT_TRUE(std::isnan(gpio1_a_o1_c.get_value().value())); + ASSERT_TRUE(std::isnan(gpio2_vac_c.get_value().value())); // set some new values in commands - gpio1_a_o1_c.set_value(0.111); - gpio2_vac_c.set_value(0.222); + ASSERT_TRUE(gpio1_a_o1_c.set_value(0.111)); + ASSERT_TRUE(gpio2_vac_c.set_value(0.222)); // State values should not be changed - ASSERT_TRUE(std::isnan(gpio1_a_o1_s.get_value())); - ASSERT_TRUE(std::isnan(gpio2_vac_s.get_value())); - ASSERT_EQ(0.111, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.222, gpio2_vac_c.get_value()); + ASSERT_TRUE(std::isnan(gpio1_a_o1_s.get_value().value())); + ASSERT_TRUE(std::isnan(gpio2_vac_s.get_value().value())); + ASSERT_EQ(0.111, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.222, gpio2_vac_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_TRUE(std::isnan(gpio1_a_o1_s.get_value())); - ASSERT_TRUE(std::isnan(gpio2_vac_s.get_value())); - ASSERT_EQ(0.111, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.222, gpio2_vac_c.get_value()); + ASSERT_TRUE(std::isnan(gpio1_a_o1_s.get_value().value())); + ASSERT_TRUE(std::isnan(gpio2_vac_s.get_value().value())); + ASSERT_EQ(0.111, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.222, gpio2_vac_c.get_value().value()); // read() mirrors commands + offset to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.111, gpio1_a_o1_s.get_value()); - ASSERT_EQ(0.222, gpio2_vac_s.get_value()); - ASSERT_EQ(0.111, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.222, gpio2_vac_c.get_value()); + ASSERT_EQ(0.111, gpio1_a_o1_s.get_value().value()); + ASSERT_EQ(0.222, gpio2_vac_s.get_value().value()); + ASSERT_EQ(0.111, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.222, gpio2_vac_c.get_value().value()); // set some new values in commands - gpio1_a_o1_c.set_value(0.333); - gpio2_vac_c.set_value(0.444); + ASSERT_TRUE(gpio1_a_o1_c.set_value(0.333)); + ASSERT_TRUE(gpio2_vac_c.set_value(0.444)); // state values should not be changed - ASSERT_EQ(0.111, gpio1_a_o1_s.get_value()); - ASSERT_EQ(0.222, gpio2_vac_s.get_value()); - ASSERT_EQ(0.333, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.444, gpio2_vac_c.get_value()); + ASSERT_EQ(0.111, gpio1_a_o1_s.get_value().value()); + ASSERT_EQ(0.222, gpio2_vac_s.get_value().value()); + ASSERT_EQ(0.333, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.444, gpio2_vac_c.get_value().value()); // check other functionalities are working well generic_system_functional_test(urdf, hardware_name); @@ -1807,52 +1807,52 @@ void TestGenericSystem::test_generic_system_with_mock_gpio_commands( hardware_interface::LoanedCommandInterface gpio2_vac_c = rm.claim_command_interface("flange_vacuum/vacuum"); - EXPECT_TRUE(std::isnan(gpio1_a_o1_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_i1_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_o2_s.get_value())); - EXPECT_TRUE(std::isnan(gpio2_vac_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_o1_c.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_i1_c.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_i2_c.get_value())); - EXPECT_TRUE(std::isnan(gpio2_vac_c.get_value())); + EXPECT_TRUE(std::isnan(gpio1_a_o1_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_i1_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_o2_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio2_vac_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_o1_c.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_i1_c.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_i2_c.get_value().value())); + EXPECT_TRUE(std::isnan(gpio2_vac_c.get_value().value())); // set some new values in commands - gpio1_a_o1_c.set_value(0.11); - gpio1_a_i1_c.set_value(0.33); - gpio1_a_i2_c.set_value(1.11); - gpio2_vac_c.set_value(2.22); + ASSERT_TRUE(gpio1_a_o1_c.set_value(0.11)); + ASSERT_TRUE(gpio1_a_i1_c.set_value(0.33)); + ASSERT_TRUE(gpio1_a_i2_c.set_value(1.11)); + ASSERT_TRUE(gpio2_vac_c.set_value(2.22)); // State values should not be changed - EXPECT_TRUE(std::isnan(gpio1_a_o1_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_i1_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_o2_s.get_value())); - EXPECT_TRUE(std::isnan(gpio2_vac_s.get_value())); - ASSERT_EQ(0.11, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.33, gpio1_a_i1_c.get_value()); - ASSERT_EQ(1.11, gpio1_a_i2_c.get_value()); - ASSERT_EQ(2.22, gpio2_vac_c.get_value()); + EXPECT_TRUE(std::isnan(gpio1_a_o1_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_i1_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_o2_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio2_vac_s.get_value().value())); + ASSERT_EQ(0.11, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.33, gpio1_a_i1_c.get_value().value()); + ASSERT_EQ(1.11, gpio1_a_i2_c.get_value().value()); + ASSERT_EQ(2.22, gpio2_vac_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - EXPECT_TRUE(std::isnan(gpio1_a_o1_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_i1_s.get_value())); - EXPECT_TRUE(std::isnan(gpio1_a_o2_s.get_value())); - EXPECT_TRUE(std::isnan(gpio2_vac_s.get_value())); - ASSERT_EQ(0.11, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.33, gpio1_a_i1_c.get_value()); - ASSERT_EQ(1.11, gpio1_a_i2_c.get_value()); - ASSERT_EQ(2.22, gpio2_vac_c.get_value()); + EXPECT_TRUE(std::isnan(gpio1_a_o1_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_i1_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio1_a_o2_s.get_value().value())); + EXPECT_TRUE(std::isnan(gpio2_vac_s.get_value().value())); + ASSERT_EQ(0.11, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.33, gpio1_a_i1_c.get_value().value()); + ASSERT_EQ(1.11, gpio1_a_i2_c.get_value().value()); + ASSERT_EQ(2.22, gpio2_vac_c.get_value().value()); // read() mirrors commands to states rm.read(TIME, PERIOD); - ASSERT_EQ(0.11, gpio1_a_o1_s.get_value()); - ASSERT_EQ(0.33, gpio1_a_i1_s.get_value()); - ASSERT_EQ(1.11, gpio1_a_o2_s.get_value()); - ASSERT_EQ(2.22, gpio2_vac_s.get_value()); - ASSERT_EQ(0.11, gpio1_a_o1_c.get_value()); - ASSERT_EQ(0.33, gpio1_a_i1_c.get_value()); - ASSERT_EQ(1.11, gpio1_a_i2_c.get_value()); - ASSERT_EQ(2.22, gpio2_vac_c.get_value()); + ASSERT_EQ(0.11, gpio1_a_o1_s.get_value().value()); + ASSERT_EQ(0.33, gpio1_a_i1_s.get_value().value()); + ASSERT_EQ(1.11, gpio1_a_o2_s.get_value().value()); + ASSERT_EQ(2.22, gpio2_vac_s.get_value().value()); + ASSERT_EQ(0.11, gpio1_a_o1_c.get_value().value()); + ASSERT_EQ(0.33, gpio1_a_i1_c.get_value().value()); + ASSERT_EQ(1.11, gpio1_a_i2_c.get_value().value()); + ASSERT_EQ(2.22, gpio2_vac_c.get_value().value()); } TEST_F(TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio_mock_command) @@ -1896,9 +1896,9 @@ TEST_F(TestGenericSystem, sensor_with_initial_value) hardware_interface::LoanedStateInterface force_z_s = rm.claim_state_interface("force_sensor/force.z"); - ASSERT_EQ(0.0, force_x_s.get_value()); - ASSERT_EQ(0.0, force_y_s.get_value()); - ASSERT_EQ(0.0, force_z_s.get_value()); + ASSERT_EQ(0.0, force_x_s.get_value().value()); + ASSERT_EQ(0.0, force_y_s.get_value().value()); + ASSERT_EQ(0.0, force_z_s.get_value().value()); } TEST_F(TestGenericSystem, gpio_with_initial_value) @@ -1917,7 +1917,7 @@ TEST_F(TestGenericSystem, gpio_with_initial_value) // Check initial values hardware_interface::LoanedStateInterface state = rm.claim_state_interface("sample_io/output_1"); - ASSERT_EQ(1, state.get_value()); + ASSERT_EQ(1, state.get_value().value()); } TEST_F(TestGenericSystem, simple_dynamics_pos_vel_acc_control_modes_interfaces) @@ -1961,16 +1961,16 @@ TEST_F(TestGenericSystem, simple_dynamics_pos_vel_acc_control_modes_interfaces) hardware_interface::LoanedCommandInterface j2a_c = rm.claim_command_interface("joint2/acceleration"); - EXPECT_EQ(3.45, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(2.78, j2p_s.get_value()); - EXPECT_EQ(0.0, j2v_s.get_value()); - EXPECT_EQ(0.0, j2a_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); - ASSERT_TRUE(std::isnan(j2a_c.get_value())); + EXPECT_EQ(3.45, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(2.78, j2p_s.get_value().value()); + EXPECT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_EQ(0.0, j2a_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2a_c.get_value().value())); // Test error management in prepare mode switch ASSERT_EQ( // joint2 has non 'position', 'velocity', or 'acceleration' interface @@ -1989,131 +1989,131 @@ TEST_F(TestGenericSystem, simple_dynamics_pos_vel_acc_control_modes_interfaces) true); // set some new values in commands - j1p_c.set_value(0.11); - j2a_c.set_value(3.5); + ASSERT_TRUE(j1p_c.set_value(0.11)); + ASSERT_TRUE(j2a_c.set_value(3.5)); // State values should not be changed - EXPECT_EQ(3.45, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(2.78, j2p_s.get_value()); - EXPECT_EQ(0.0, j2v_s.get_value()); - EXPECT_EQ(0.0, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(3.45, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(2.78, j2p_s.get_value().value()); + EXPECT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_EQ(0.0, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - EXPECT_EQ(3.45, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(2.78, j2p_s.get_value()); - EXPECT_EQ(0.0, j2v_s.get_value()); - EXPECT_EQ(0.0, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(3.45, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(2.78, j2p_s.get_value().value()); + EXPECT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_EQ(0.0, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // read() mirrors commands to states and calculate dynamics rm.read(TIME, PERIOD); - EXPECT_EQ(0.11, j1p_s.get_value()); - EXPECT_EQ(-33.4, j1v_s.get_value()); - EXPECT_NEAR(-334.0, j1a_s.get_value(), COMPARE_DELTA); - EXPECT_EQ(2.78, j2p_s.get_value()); - EXPECT_EQ(0.0, j2v_s.get_value()); - EXPECT_EQ(3.5, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.11, j1p_s.get_value().value()); + EXPECT_EQ(-33.4, j1v_s.get_value().value()); + EXPECT_NEAR(-334.0, j1a_s.get_value().value(), COMPARE_DELTA); + EXPECT_EQ(2.78, j2p_s.get_value().value()); + EXPECT_EQ(0.0, j2v_s.get_value().value()); + EXPECT_EQ(3.5, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // read() mirrors commands to states and calculate dynamics rm.read(TIME, PERIOD); - EXPECT_EQ(0.11, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_NEAR(334.0, j1a_s.get_value(), COMPARE_DELTA); - EXPECT_EQ(2.78, j2p_s.get_value()); - EXPECT_NEAR(0.35, j2v_s.get_value(), COMPARE_DELTA); - EXPECT_EQ(3.5, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.11, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_NEAR(334.0, j1a_s.get_value().value(), COMPARE_DELTA); + EXPECT_EQ(2.78, j2p_s.get_value().value()); + EXPECT_NEAR(0.35, j2v_s.get_value().value(), COMPARE_DELTA); + EXPECT_EQ(3.5, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // read() mirrors commands to states and calculate dynamics rm.read(TIME, PERIOD); - EXPECT_EQ(0.11, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(2.815, j2p_s.get_value()); - EXPECT_NEAR(0.7, j2v_s.get_value(), COMPARE_DELTA); - EXPECT_EQ(3.5, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_TRUE(std::isnan(j1v_c.get_value())); - ASSERT_TRUE(std::isnan(j2v_c.get_value())); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.11, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(2.815, j2p_s.get_value().value()); + EXPECT_NEAR(0.7, j2v_s.get_value().value(), COMPARE_DELTA); + EXPECT_EQ(3.5, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_TRUE(std::isnan(j1v_c.get_value().value())); + ASSERT_TRUE(std::isnan(j2v_c.get_value().value())); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // switch controller mode as controller manager is doing ASSERT_EQ(rm.prepare_command_mode_switch({"joint1/velocity", "joint2/velocity"}, {}), true); ASSERT_EQ(rm.perform_command_mode_switch({"joint1/velocity", "joint2/velocity"}, {}), true); // set some new values in commands - j1v_c.set_value(0.5); - j2v_c.set_value(2.0); + ASSERT_TRUE(j1v_c.set_value(0.5)); + ASSERT_TRUE(j2v_c.set_value(2.0)); // State values should not be changed - EXPECT_EQ(0.11, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(2.815, j2p_s.get_value()); - EXPECT_NEAR(0.7, j2v_s.get_value(), COMPARE_DELTA); - EXPECT_EQ(3.5, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.5, j1v_c.get_value()); - ASSERT_EQ(2.0, j2v_c.get_value()); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.11, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(2.815, j2p_s.get_value().value()); + EXPECT_NEAR(0.7, j2v_s.get_value().value(), COMPARE_DELTA); + EXPECT_EQ(3.5, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.5, j1v_c.get_value().value()); + ASSERT_EQ(2.0, j2v_c.get_value().value()); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - EXPECT_EQ(0.11, j1p_s.get_value()); - EXPECT_EQ(0.0, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(2.815, j2p_s.get_value()); - EXPECT_NEAR(0.7, j2v_s.get_value(), COMPARE_DELTA); - EXPECT_EQ(3.5, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.5, j1v_c.get_value()); - ASSERT_EQ(2.0, j2v_c.get_value()); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.11, j1p_s.get_value().value()); + EXPECT_EQ(0.0, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(2.815, j2p_s.get_value().value()); + EXPECT_NEAR(0.7, j2v_s.get_value().value(), COMPARE_DELTA); + EXPECT_EQ(3.5, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.5, j1v_c.get_value().value()); + ASSERT_EQ(2.0, j2v_c.get_value().value()); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // read() mirrors commands to states and calculate dynamics (both velocity mode) rm.read(TIME, PERIOD); - EXPECT_EQ(0.11, j1p_s.get_value()); - EXPECT_EQ(0.5, j1v_s.get_value()); - EXPECT_EQ(5.0, j1a_s.get_value()); - EXPECT_EQ(2.885, j2p_s.get_value()); - EXPECT_EQ(2.0, j2v_s.get_value()); - EXPECT_NEAR(13.0, j2a_s.get_value(), COMPARE_DELTA); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.5, j1v_c.get_value()); - ASSERT_EQ(2.0, j2v_c.get_value()); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.11, j1p_s.get_value().value()); + EXPECT_EQ(0.5, j1v_s.get_value().value()); + EXPECT_EQ(5.0, j1a_s.get_value().value()); + EXPECT_EQ(2.885, j2p_s.get_value().value()); + EXPECT_EQ(2.0, j2v_s.get_value().value()); + EXPECT_NEAR(13.0, j2a_s.get_value().value(), COMPARE_DELTA); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.5, j1v_c.get_value().value()); + ASSERT_EQ(2.0, j2v_c.get_value().value()); + ASSERT_EQ(3.5, j2a_c.get_value().value()); // read() mirrors commands to states and calculate dynamics (both velocity mode) rm.read(TIME, PERIOD); - EXPECT_EQ(0.16, j1p_s.get_value()); - EXPECT_EQ(0.5, j1v_s.get_value()); - EXPECT_EQ(0.0, j1a_s.get_value()); - EXPECT_EQ(3.085, j2p_s.get_value()); - EXPECT_EQ(2.0, j2v_s.get_value()); - EXPECT_EQ(0.0, j2a_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); - ASSERT_EQ(0.5, j1v_c.get_value()); - ASSERT_EQ(2.0, j2v_c.get_value()); - ASSERT_EQ(3.5, j2a_c.get_value()); + EXPECT_EQ(0.16, j1p_s.get_value().value()); + EXPECT_EQ(0.5, j1v_s.get_value().value()); + EXPECT_EQ(0.0, j1a_s.get_value().value()); + EXPECT_EQ(3.085, j2p_s.get_value().value()); + EXPECT_EQ(2.0, j2v_s.get_value().value()); + EXPECT_EQ(0.0, j2a_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); + ASSERT_EQ(0.5, j1v_c.get_value().value()); + ASSERT_EQ(2.0, j2v_c.get_value().value()); + ASSERT_EQ(3.5, j2a_c.get_value().value()); } TEST_F(TestGenericSystem, disabled_commands_flag_is_active) @@ -2138,29 +2138,29 @@ TEST_F(TestGenericSystem, disabled_commands_flag_is_active) hardware_interface::LoanedStateInterface j1v_s = rm.claim_state_interface("joint1/velocity"); hardware_interface::LoanedCommandInterface j1p_c = rm.claim_command_interface("joint1/position"); - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_TRUE(std::isnan(j1p_c.get_value())); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value().value())); // set some new values in commands - j1p_c.set_value(0.11); + ASSERT_TRUE(j1p_c.set_value(0.11)); // State values should not be changed - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); // write() does not change values rm.write(TIME, PERIOD); - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); // read() also does not change values rm.read(TIME, PERIOD); - ASSERT_EQ(3.45, j1p_s.get_value()); - ASSERT_EQ(0.0, j1v_s.get_value()); - ASSERT_EQ(0.11, j1p_c.get_value()); + ASSERT_EQ(3.45, j1p_s.get_value().value()); + ASSERT_EQ(0.0, j1v_s.get_value().value()); + ASSERT_EQ(0.11, j1p_c.get_value().value()); } TEST_F(TestGenericSystem, prepare_command_mode_switch_works_with_all_example_tags) diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index 06ef8a0e42..36dbfffe02 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -749,7 +749,7 @@ TEST(TestComponentInterfaces, dummy_actuator) EXPECT_EQ("joint1", command_interfaces[0]->get_prefix_name()); double velocity_value = 1.0; - command_interfaces[0]->set_value(velocity_value); // velocity + ASSERT_TRUE(command_interfaces[0]->set_value(velocity_value)); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); // Noting should change because it is UNCONFIGURED @@ -757,8 +757,8 @@ TEST(TestComponentInterfaces, dummy_actuator) { ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); - ASSERT_TRUE(std::isnan(state_interfaces[0]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[1]->get_value())); // velocity + ASSERT_TRUE(std::isnan(state_interfaces[0]->get_value().value())); // position value + ASSERT_TRUE(std::isnan(state_interfaces[1]->get_value().value())); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -772,8 +772,10 @@ TEST(TestComponentInterfaces, dummy_actuator) { ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); - EXPECT_EQ(step * velocity_value, state_interfaces[0]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[1]->get_value()); // velocity + EXPECT_EQ( + step * velocity_value, state_interfaces[0]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, state_interfaces[1]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -787,8 +789,10 @@ TEST(TestComponentInterfaces, dummy_actuator) { ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); - EXPECT_EQ((10 + step) * velocity_value, state_interfaces[0]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[1]->get_value()); // velocity + EXPECT_EQ( + (10 + step) * velocity_value, + state_interfaces[0]->get_value().value()); // position value + EXPECT_EQ(velocity_value, state_interfaces[1]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -802,8 +806,9 @@ TEST(TestComponentInterfaces, dummy_actuator) { ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); - EXPECT_EQ(20 * velocity_value, state_interfaces[0]->get_value()); // position value - EXPECT_EQ(0, state_interfaces[1]->get_value()); // velocity + EXPECT_EQ( + 20 * velocity_value, state_interfaces[0]->get_value().value()); // position value + EXPECT_EQ(0, state_interfaces[1]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -866,7 +871,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default) double velocity_value = 1.0; auto ci_joint1_vel = test_components::vector_contains(command_interfaces, "joint1/velocity").second; - command_interfaces[ci_joint1_vel]->set_value(velocity_value); // velocity + ASSERT_TRUE(command_interfaces[ci_joint1_vel]->set_value(velocity_value)); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); // Noting should change because it is UNCONFIGURED @@ -876,8 +881,10 @@ TEST(TestComponentInterfaces, dummy_actuator_default) { ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); - ASSERT_TRUE(std::isnan(state_interfaces[si_joint1_pos]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[si_joint1_vel]->get_value())); // velocity + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint1_pos]->get_value().value())); // position value + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint1_vel]->get_value().value())); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -892,8 +899,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default) ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); EXPECT_EQ( - step * velocity_value, state_interfaces[si_joint1_pos]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[si_joint1_vel]->get_value()); // velocity + step * velocity_value, + state_interfaces[si_joint1_pos]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, + state_interfaces[si_joint1_vel]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -909,8 +919,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default) EXPECT_EQ( (10 + step) * velocity_value, - state_interfaces[si_joint1_pos]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[si_joint1_vel]->get_value()); // velocity + state_interfaces[si_joint1_pos]->get_value().value()); // position value + EXPECT_EQ( + velocity_value, state_interfaces[si_joint1_vel]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -924,8 +935,10 @@ TEST(TestComponentInterfaces, dummy_actuator_default) { ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD)); - EXPECT_EQ(20 * velocity_value, state_interfaces[si_joint1_pos]->get_value()); // position value - EXPECT_EQ(0, state_interfaces[si_joint1_vel]->get_value()); // velocity + EXPECT_EQ( + 20 * velocity_value, + state_interfaces[si_joint1_pos]->get_value().value()); // position value + EXPECT_EQ(0, state_interfaces[si_joint1_vel]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD)); } @@ -953,21 +966,21 @@ TEST(TestComponentInterfaces, dummy_sensor) EXPECT_EQ("sens1/voltage", state_interfaces[0]->get_name()); EXPECT_EQ("voltage", state_interfaces[0]->get_interface_name()); EXPECT_EQ("sens1", state_interfaces[0]->get_prefix_name()); - EXPECT_TRUE(std::isnan(state_interfaces[0]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[0]->get_value().value())); // Not updated because is is UNCONFIGURED sensor_hw.read(TIME, PERIOD); - EXPECT_TRUE(std::isnan(state_interfaces[0]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[0]->get_value().value())); // Updated because is is INACTIVE state = sensor_hw.configure(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::INACTIVE, state.label()); - EXPECT_EQ(0.0, state_interfaces[0]->get_value()); + EXPECT_EQ(0.0, state_interfaces[0]->get_value().value()); // It can read now sensor_hw.read(TIME, PERIOD); - EXPECT_EQ(0x666, state_interfaces[0]->get_value()); + EXPECT_EQ(0x666, state_interfaces[0]->get_value().value()); } // END @@ -996,23 +1009,23 @@ TEST(TestComponentInterfaces, dummy_sensor_default) EXPECT_EQ("sens1/voltage", state_interfaces[position]->get_name()); EXPECT_EQ("voltage", state_interfaces[position]->get_interface_name()); EXPECT_EQ("sens1", state_interfaces[position]->get_prefix_name()); - EXPECT_TRUE(std::isnan(state_interfaces[position]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[position]->get_value().value())); } // Not updated because is is UNCONFIGURED auto si_sens1_vol = test_components::vector_contains(state_interfaces, "sens1/voltage").second; sensor_hw.read(TIME, PERIOD); - EXPECT_TRUE(std::isnan(state_interfaces[si_sens1_vol]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[si_sens1_vol]->get_value().value())); // Updated because is is INACTIVE state = sensor_hw.configure(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::INACTIVE, state.label()); - EXPECT_EQ(0.0, state_interfaces[si_sens1_vol]->get_value()); + EXPECT_EQ(0.0, state_interfaces[si_sens1_vol]->get_value().value()); // It can read now sensor_hw.read(TIME, PERIOD); - EXPECT_EQ(0x666, state_interfaces[si_sens1_vol]->get_value()); + EXPECT_EQ(0x666, state_interfaces[si_sens1_vol]->get_value().value()); } TEST(TestComponentInterfaces, dummy_sensor_default_joint) @@ -1042,7 +1055,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint) EXPECT_EQ("sens1/voltage", state_interfaces[si_sens1_vol]->get_name()); EXPECT_EQ("voltage", state_interfaces[si_sens1_vol]->get_interface_name()); EXPECT_EQ("sens1", state_interfaces[si_sens1_vol]->get_prefix_name()); - EXPECT_TRUE(std::isnan(state_interfaces[si_sens1_vol]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[si_sens1_vol]->get_value().value())); auto [contains_joint1_pos, si_joint1_pos] = test_components::vector_contains(state_interfaces, "joint1/position"); @@ -1050,24 +1063,24 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint) EXPECT_EQ("joint1/position", state_interfaces[si_joint1_pos]->get_name()); EXPECT_EQ("position", state_interfaces[si_joint1_pos]->get_interface_name()); EXPECT_EQ("joint1", state_interfaces[si_joint1_pos]->get_prefix_name()); - EXPECT_TRUE(std::isnan(state_interfaces[si_joint1_pos]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[si_joint1_pos]->get_value().value())); // Not updated because is is UNCONFIGURED sensor_hw.read(TIME, PERIOD); - EXPECT_TRUE(std::isnan(state_interfaces[si_sens1_vol]->get_value())); - EXPECT_TRUE(std::isnan(state_interfaces[si_joint1_pos]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[si_sens1_vol]->get_value().value())); + EXPECT_TRUE(std::isnan(state_interfaces[si_joint1_pos]->get_value().value())); // Updated because is is INACTIVE state = sensor_hw.configure(); ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, state.id()); ASSERT_EQ(hardware_interface::lifecycle_state_names::INACTIVE, state.label()); - EXPECT_EQ(0.0, state_interfaces[si_sens1_vol]->get_value()); - EXPECT_EQ(10.0, state_interfaces[si_joint1_pos]->get_value()); + EXPECT_EQ(0.0, state_interfaces[si_sens1_vol]->get_value().value()); + EXPECT_EQ(10.0, state_interfaces[si_joint1_pos]->get_value().value()); // It can read now sensor_hw.read(TIME, PERIOD); - EXPECT_EQ(0x666, state_interfaces[si_sens1_vol]->get_value()); - EXPECT_EQ(0x777, state_interfaces[si_joint1_pos]->get_value()); + EXPECT_EQ(0x666, state_interfaces[si_sens1_vol]->get_value().value()); + EXPECT_EQ(0x777, state_interfaces[si_joint1_pos]->get_value().value()); } // BEGIN (Handle export change): for backward compatibility @@ -1116,9 +1129,9 @@ TEST(TestComponentInterfaces, dummy_system) EXPECT_EQ("joint3", command_interfaces[2]->get_prefix_name()); double velocity_value = 1.0; - command_interfaces[0]->set_value(velocity_value); // velocity - command_interfaces[1]->set_value(velocity_value); // velocity - command_interfaces[2]->set_value(velocity_value); // velocity + ASSERT_TRUE(command_interfaces[0]->set_value(velocity_value)); // velocity + ASSERT_TRUE(command_interfaces[1]->set_value(velocity_value)); // velocity + ASSERT_TRUE(command_interfaces[2]->set_value(velocity_value)); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); // Noting should change because it is UNCONFIGURED @@ -1126,12 +1139,12 @@ TEST(TestComponentInterfaces, dummy_system) { ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); - ASSERT_TRUE(std::isnan(state_interfaces[0]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[1]->get_value())); // velocity - ASSERT_TRUE(std::isnan(state_interfaces[2]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[3]->get_value())); // velocity - ASSERT_TRUE(std::isnan(state_interfaces[4]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[5]->get_value())); // velocity + ASSERT_TRUE(std::isnan(state_interfaces[0]->get_value().value())); // position value + ASSERT_TRUE(std::isnan(state_interfaces[1]->get_value().value())); // velocity + ASSERT_TRUE(std::isnan(state_interfaces[2]->get_value().value())); // position value + ASSERT_TRUE(std::isnan(state_interfaces[3]->get_value().value())); // velocity + ASSERT_TRUE(std::isnan(state_interfaces[4]->get_value().value())); // position value + ASSERT_TRUE(std::isnan(state_interfaces[5]->get_value().value())); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1145,12 +1158,18 @@ TEST(TestComponentInterfaces, dummy_system) { ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); - EXPECT_EQ(step * velocity_value, state_interfaces[0]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[1]->get_value()); // velocity - EXPECT_EQ(step * velocity_value, state_interfaces[2]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[3]->get_value()); // velocity - EXPECT_EQ(step * velocity_value, state_interfaces[4]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[5]->get_value()); // velocity + EXPECT_EQ( + step * velocity_value, state_interfaces[0]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, state_interfaces[1]->get_value().value()); // velocity + EXPECT_EQ( + step * velocity_value, state_interfaces[2]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, state_interfaces[3]->get_value().value()); // velocity + EXPECT_EQ( + step * velocity_value, state_interfaces[4]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, state_interfaces[5]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1164,12 +1183,18 @@ TEST(TestComponentInterfaces, dummy_system) { ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); - EXPECT_EQ((10 + step) * velocity_value, state_interfaces[0]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[1]->get_value()); // velocity - EXPECT_EQ((10 + step) * velocity_value, state_interfaces[2]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[3]->get_value()); // velocity - EXPECT_EQ((10 + step) * velocity_value, state_interfaces[4]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[5]->get_value()); // velocity + EXPECT_EQ( + (10 + step) * velocity_value, + state_interfaces[0]->get_value().value()); // position value + EXPECT_EQ(velocity_value, state_interfaces[1]->get_value().value()); // velocity + EXPECT_EQ( + (10 + step) * velocity_value, + state_interfaces[2]->get_value().value()); // position value + EXPECT_EQ(velocity_value, state_interfaces[3]->get_value().value()); // velocity + EXPECT_EQ( + (10 + step) * velocity_value, + state_interfaces[4]->get_value().value()); // position value + EXPECT_EQ(velocity_value, state_interfaces[5]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1183,12 +1208,15 @@ TEST(TestComponentInterfaces, dummy_system) { ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); - EXPECT_EQ(20 * velocity_value, state_interfaces[0]->get_value()); // position value - EXPECT_EQ(0.0, state_interfaces[1]->get_value()); // velocity - EXPECT_EQ(20 * velocity_value, state_interfaces[2]->get_value()); // position value - EXPECT_EQ(0.0, state_interfaces[3]->get_value()); // velocity - EXPECT_EQ(20 * velocity_value, state_interfaces[4]->get_value()); // position value - EXPECT_EQ(0.0, state_interfaces[5]->get_value()); // velocity + EXPECT_EQ( + 20 * velocity_value, state_interfaces[0]->get_value().value()); // position value + EXPECT_EQ(0.0, state_interfaces[1]->get_value().value()); // velocity + EXPECT_EQ( + 20 * velocity_value, state_interfaces[2]->get_value().value()); // position value + EXPECT_EQ(0.0, state_interfaces[3]->get_value().value()); // velocity + EXPECT_EQ( + 20 * velocity_value, state_interfaces[4]->get_value().value()); // position value + EXPECT_EQ(0.0, state_interfaces[5]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1303,9 +1331,9 @@ TEST(TestComponentInterfaces, dummy_system_default) auto ci_joint3_vel = test_components::vector_contains(command_interfaces, "joint3/velocity").second; double velocity_value = 1.0; - command_interfaces[ci_joint1_vel]->set_value(velocity_value); // velocity - command_interfaces[ci_joint2_vel]->set_value(velocity_value); // velocity - command_interfaces[ci_joint3_vel]->set_value(velocity_value); // velocity + ASSERT_TRUE(command_interfaces[ci_joint1_vel]->set_value(velocity_value)); // velocity + ASSERT_TRUE(command_interfaces[ci_joint2_vel]->set_value(velocity_value)); // velocity + ASSERT_TRUE(command_interfaces[ci_joint3_vel]->set_value(velocity_value)); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); // Noting should change because it is UNCONFIGURED @@ -1319,12 +1347,18 @@ TEST(TestComponentInterfaces, dummy_system_default) { ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); - ASSERT_TRUE(std::isnan(state_interfaces[si_joint1_pos]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[si_joint1_vel]->get_value())); // velocity - ASSERT_TRUE(std::isnan(state_interfaces[si_joint2_pos]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[si_joint2_vel]->get_value())); // velocity - ASSERT_TRUE(std::isnan(state_interfaces[si_joint3_pos]->get_value())); // position value - ASSERT_TRUE(std::isnan(state_interfaces[si_joint3_vel]->get_value())); // velocity + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint1_pos]->get_value().value())); // position value + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint1_vel]->get_value().value())); // velocity + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint2_pos]->get_value().value())); // position value + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint2_vel]->get_value().value())); // velocity + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint3_pos]->get_value().value())); // position value + ASSERT_TRUE( + std::isnan(state_interfaces[si_joint3_vel]->get_value().value())); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1339,14 +1373,23 @@ TEST(TestComponentInterfaces, dummy_system_default) ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); EXPECT_EQ( - step * velocity_value, state_interfaces[si_joint1_pos]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[si_joint1_vel]->get_value()); // velocity + step * velocity_value, + state_interfaces[si_joint1_pos]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, + state_interfaces[si_joint1_vel]->get_value().value()); // velocity EXPECT_EQ( - step * velocity_value, state_interfaces[si_joint2_pos]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[si_joint2_vel]->get_value()); // velocity + step * velocity_value, + state_interfaces[si_joint2_pos]->get_value().value()); // position value EXPECT_EQ( - step * velocity_value, state_interfaces[si_joint3_pos]->get_value()); // position value - EXPECT_EQ(step ? velocity_value : 0, state_interfaces[si_joint3_vel]->get_value()); // velocity + step ? velocity_value : 0, + state_interfaces[si_joint2_vel]->get_value().value()); // velocity + EXPECT_EQ( + step * velocity_value, + state_interfaces[si_joint3_pos]->get_value().value()); // position value + EXPECT_EQ( + step ? velocity_value : 0, + state_interfaces[si_joint3_vel]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1362,16 +1405,19 @@ TEST(TestComponentInterfaces, dummy_system_default) EXPECT_EQ( (10 + step) * velocity_value, - state_interfaces[si_joint1_pos]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[si_joint1_vel]->get_value()); // velocity + state_interfaces[si_joint1_pos]->get_value().value()); // position value + EXPECT_EQ( + velocity_value, state_interfaces[si_joint1_vel]->get_value().value()); // velocity EXPECT_EQ( (10 + step) * velocity_value, - state_interfaces[si_joint2_pos]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[si_joint2_vel]->get_value()); // velocity + state_interfaces[si_joint2_pos]->get_value().value()); // position value + EXPECT_EQ( + velocity_value, state_interfaces[si_joint2_vel]->get_value().value()); // velocity EXPECT_EQ( (10 + step) * velocity_value, - state_interfaces[si_joint3_pos]->get_value()); // position value - EXPECT_EQ(velocity_value, state_interfaces[si_joint3_vel]->get_value()); // velocity + state_interfaces[si_joint3_pos]->get_value().value()); // position value + EXPECT_EQ( + velocity_value, state_interfaces[si_joint3_vel]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1385,12 +1431,18 @@ TEST(TestComponentInterfaces, dummy_system_default) { ASSERT_EQ(hardware_interface::return_type::OK, system_hw.read(TIME, PERIOD)); - EXPECT_EQ(20 * velocity_value, state_interfaces[si_joint1_pos]->get_value()); // position value - EXPECT_EQ(0.0, state_interfaces[si_joint1_vel]->get_value()); // velocity - EXPECT_EQ(20 * velocity_value, state_interfaces[si_joint2_pos]->get_value()); // position value - EXPECT_EQ(0.0, state_interfaces[si_joint2_vel]->get_value()); // velocity - EXPECT_EQ(20 * velocity_value, state_interfaces[si_joint3_pos]->get_value()); // position value - EXPECT_EQ(0.0, state_interfaces[si_joint3_vel]->get_value()); // velocity + EXPECT_EQ( + 20 * velocity_value, + state_interfaces[si_joint1_pos]->get_value().value()); // position value + EXPECT_EQ(0.0, state_interfaces[si_joint1_vel]->get_value().value()); // velocity + EXPECT_EQ( + 20 * velocity_value, + state_interfaces[si_joint2_pos]->get_value().value()); // position value + EXPECT_EQ(0.0, state_interfaces[si_joint2_vel]->get_value().value()); // velocity + EXPECT_EQ( + 20 * velocity_value, + state_interfaces[si_joint3_pos]->get_value().value()); // position value + EXPECT_EQ(0.0, state_interfaces[si_joint3_vel]->get_value().value()); // velocity ASSERT_EQ(hardware_interface::return_type::OK, system_hw.write(TIME, PERIOD)); } @@ -1467,8 +1519,8 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior) // activate again and expect reset values state = actuator_hw.configure(); - EXPECT_EQ(state_interfaces[0]->get_value(), 0.0); - EXPECT_EQ(command_interfaces[0]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[0]->get_value().value(), 0.0); + EXPECT_EQ(command_interfaces[0]->get_value().value(), 0.0); state = actuator_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1540,8 +1592,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) auto ci_joint1_vel = test_components::vector_contains(command_interfaces, "joint1/velocity").second; state = actuator_hw.configure(); - EXPECT_EQ(state_interfaces[si_joint1_pos]->get_value(), 0.0); - EXPECT_EQ(command_interfaces[ci_joint1_vel]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[si_joint1_pos]->get_value().value(), 0.0); + EXPECT_EQ(command_interfaces[ci_joint1_vel]->get_value().value(), 0.0); state = actuator_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1602,8 +1654,8 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior) // activate again and expect reset values state = actuator_hw.configure(); - EXPECT_EQ(state_interfaces[0]->get_value(), 0.0); - EXPECT_EQ(command_interfaces[0]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[0]->get_value().value(), 0.0); + EXPECT_EQ(command_interfaces[0]->get_value().value(), 0.0); state = actuator_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1674,8 +1726,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) auto ci_joint1_vel = test_components::vector_contains(command_interfaces, "joint1/velocity").second; state = actuator_hw.configure(); - EXPECT_EQ(state_interfaces[si_joint1_pos]->get_value(), 0.0); - EXPECT_EQ(command_interfaces[ci_joint1_vel]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[si_joint1_pos]->get_value().value(), 0.0); + EXPECT_EQ(command_interfaces[ci_joint1_vel]->get_value().value(), 0.0); state = actuator_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1739,7 +1791,7 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior) // activate again and expect reset values state = sensor_hw.configure(); - EXPECT_EQ(state_interfaces[0]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[0]->get_value().value(), 0.0); state = sensor_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1807,7 +1859,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) // activate again and expect reset values auto si_joint1_vol = test_components::vector_contains(state_interfaces, "sens1/voltage").second; state = sensor_hw.configure(); - EXPECT_EQ(state_interfaces[si_joint1_vol]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[si_joint1_vol]->get_value().value(), 0.0); state = sensor_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1867,11 +1919,11 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior) state = system_hw.configure(); for (auto index = 0ul; index < 6; ++index) { - EXPECT_EQ(state_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[index]->get_value().value(), 0.0); } for (auto index = 0ul; index < 3; ++index) { - EXPECT_EQ(command_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(command_interfaces[index]->get_value().value(), 0.0); } state = system_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -1940,11 +1992,11 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) state = system_hw.configure(); for (auto index = 0ul; index < 6; ++index) { - EXPECT_EQ(state_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[index]->get_value().value(), 0.0); } for (auto index = 0ul; index < 3; ++index) { - EXPECT_EQ(command_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(command_interfaces[index]->get_value().value(), 0.0); } state = system_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -2007,11 +2059,11 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior) state = system_hw.configure(); for (auto index = 0ul; index < 6; ++index) { - EXPECT_EQ(state_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[index]->get_value().value(), 0.0); } for (auto index = 0ul; index < 3; ++index) { - EXPECT_EQ(command_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(command_interfaces[index]->get_value().value(), 0.0); } state = system_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); @@ -2080,11 +2132,11 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) state = system_hw.configure(); for (auto index = 0ul; index < 6; ++index) { - EXPECT_EQ(state_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(state_interfaces[index]->get_value().value(), 0.0); } for (auto index = 0ul; index < 3; ++index) { - EXPECT_EQ(command_interfaces[index]->get_value(), 0.0); + EXPECT_EQ(command_interfaces[index]->get_value().value(), 0.0); } state = system_hw.activate(); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id()); diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index 7335f9420a..99428a4496 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -244,7 +244,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) EXPECT_EQ("sens1/voltage", state_interfaces[position]->get_name()); EXPECT_EQ("voltage", state_interfaces[position]->get_interface_name()); EXPECT_EQ("sens1", state_interfaces[position]->get_prefix_name()); - EXPECT_TRUE(std::isnan(state_interfaces[position]->get_value())); + EXPECT_TRUE(std::isnan(state_interfaces[position]->get_value().value())); } { auto [contains, position] = diff --git a/hardware_interface/test/test_handle.cpp b/hardware_interface/test/test_handle.cpp index 201a8b69d5..2f07f71cad 100644 --- a/hardware_interface/test/test_handle.cpp +++ b/hardware_interface/test/test_handle.cpp @@ -31,16 +31,21 @@ TEST(TestHandle, command_interface) { double value = 1.337; CommandInterface interface{JOINT_NAME, FOO_INTERFACE, &value}; - EXPECT_DOUBLE_EQ(interface.get_value(), value); - EXPECT_NO_THROW(interface.set_value(0.0)); - EXPECT_DOUBLE_EQ(interface.get_value(), 0.0); + EXPECT_DOUBLE_EQ(interface.get_value().value(), value); + ASSERT_TRUE(interface.get_value().has_value()); + EXPECT_DOUBLE_EQ(interface.get_value().value(), value); + EXPECT_DOUBLE_EQ(interface.get_value().value(), value); + EXPECT_NO_THROW(bool status = interface.set_value(0.0)); + ASSERT_TRUE(interface.get_value().has_value()); + EXPECT_DOUBLE_EQ(interface.get_value().value(), 0.0); } TEST(TestHandle, state_interface) { double value = 1.337; StateInterface interface{JOINT_NAME, FOO_INTERFACE, &value}; - EXPECT_DOUBLE_EQ(interface.get_value(), value); + ASSERT_TRUE(interface.get_value().has_value()); + EXPECT_DOUBLE_EQ(interface.get_value().value(), value); // interface.set_value(5); compiler error, no set_value function } @@ -55,17 +60,19 @@ TEST(TestHandle, name_getters_work) TEST(TestHandle, value_methods_throw_for_nullptr) { CommandInterface handle{JOINT_NAME, FOO_INTERFACE}; - EXPECT_ANY_THROW(handle.get_value()); - EXPECT_ANY_THROW(handle.set_value(0.0)); + EXPECT_ANY_THROW(handle.get_value().value()); + EXPECT_ANY_THROW(bool status = handle.set_value(0.0)); } TEST(TestHandle, value_methods_work_on_non_nullptr) { double value = 1.337; CommandInterface handle{JOINT_NAME, FOO_INTERFACE, &value}; - EXPECT_DOUBLE_EQ(handle.get_value(), value); - EXPECT_NO_THROW(handle.set_value(0.0)); - EXPECT_DOUBLE_EQ(handle.get_value(), 0.0); + ASSERT_TRUE(handle.get_value().has_value()); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); + EXPECT_NO_THROW(bool status_set = handle.set_value(0.0)); + ASSERT_TRUE(handle.get_value().has_value()); + EXPECT_DOUBLE_EQ(handle.get_value().value(), 0.0); } TEST(TestHandle, interface_description_state_interface_name_getters_work) diff --git a/hardware_interface_testing/test/test_resource_manager.cpp b/hardware_interface_testing/test/test_resource_manager.cpp index 65735e23f7..f79a4bc5e6 100644 --- a/hardware_interface_testing/test/test_resource_manager.cpp +++ b/hardware_interface_testing/test/test_resource_manager.cpp @@ -1284,13 +1284,13 @@ TEST_F(ResourceManagerTest, managing_controllers_reference_interfaces) EXPECT_TRUE(rm.command_interface_is_claimed(FULL_REFERENCE_INTERFACE_NAMES[2])); // access interface value - EXPECT_EQ(claimed_itf1.get_value(), 1.0); - EXPECT_EQ(claimed_itf3.get_value(), 3.0); + EXPECT_EQ(claimed_itf1.get_value().value(), 1.0); + EXPECT_EQ(claimed_itf3.get_value().value(), 3.0); claimed_itf1.set_value(11.1); claimed_itf3.set_value(33.3); - EXPECT_EQ(claimed_itf1.get_value(), 11.1); - EXPECT_EQ(claimed_itf3.get_value(), 33.3); + EXPECT_EQ(claimed_itf1.get_value().value(), 11.1); + EXPECT_EQ(claimed_itf3.get_value().value(), 33.3); EXPECT_EQ(reference_interface_values[0], 11.1); EXPECT_EQ(reference_interface_values[1], 2.0); @@ -1819,8 +1819,8 @@ class ResourceManagerTestReadWriteDifferentReadWriteRate : public ResourceManage void check_read_and_write_cycles(bool test_for_changing_values) { - double prev_act_state_value = state_itfs[0].get_value(); - double prev_system_state_value = state_itfs[1].get_value(); + double prev_act_state_value = state_itfs[0].get_value().value(); + double prev_system_state_value = state_itfs[1].get_value().value(); for (size_t i = 1; i < 100; i++) { @@ -1830,19 +1830,19 @@ class ResourceManagerTestReadWriteDifferentReadWriteRate : public ResourceManage if (i % (cm_update_rate_ / system_rw_rate_) == 0 && test_for_changing_values) { // The values are computations exactly within the test_components - prev_system_state_value = claimed_itfs[1].get_value() / 2.0; - claimed_itfs[1].set_value(claimed_itfs[1].get_value() + 20.0); + prev_system_state_value = claimed_itfs[1].get_value().value() / 2.0; + claimed_itfs[1].set_value(claimed_itfs[1].get_value().value() + 20.0); } if (i % (cm_update_rate_ / actuator_rw_rate_) == 0 && test_for_changing_values) { // The values are computations exactly within the test_components - prev_act_state_value = claimed_itfs[0].get_value() / 2.0; - claimed_itfs[0].set_value(claimed_itfs[0].get_value() + 10.0); + prev_act_state_value = claimed_itfs[0].get_value().value() / 2.0; + claimed_itfs[0].set_value(claimed_itfs[0].get_value().value() + 10.0); } // Even though we skip some read and write iterations, the state interfaces should be the same // as previous updated one until the next cycle - ASSERT_EQ(state_itfs[0].get_value(), prev_act_state_value); - ASSERT_EQ(state_itfs[1].get_value(), prev_system_state_value); + ASSERT_EQ(state_itfs[0].get_value().value(), prev_act_state_value); + ASSERT_EQ(state_itfs[1].get_value().value(), prev_system_state_value); auto [ok_write, failed_hardware_names_write] = rm->write(time, duration); EXPECT_TRUE(ok_write); EXPECT_TRUE(failed_hardware_names_write.empty()); @@ -2032,8 +2032,8 @@ class ResourceManagerTestAsyncReadWrite : public ResourceManagerTest void check_read_and_write_cycles(bool check_for_updated_values) { - double prev_act_state_value = state_itfs[0].get_value(); - double prev_system_state_value = state_itfs[1].get_value(); + double prev_act_state_value = state_itfs[0].get_value().value(); + double prev_system_state_value = state_itfs[1].get_value().value(); const double actuator_increment = 10.0; const double system_increment = 20.0; for (size_t i = 1; i < 100; i++) @@ -2045,15 +2045,17 @@ class ResourceManagerTestAsyncReadWrite : public ResourceManagerTest // The values are computations exactly within the test_components if (check_for_updated_values) { - prev_system_state_value = claimed_itfs[1].get_value() / 2.0; - prev_act_state_value = claimed_itfs[0].get_value() / 2.0; + prev_system_state_value = claimed_itfs[1].get_value().value() / 2.0; + prev_act_state_value = claimed_itfs[0].get_value().value() / 2.0; } - claimed_itfs[0].set_value(claimed_itfs[0].get_value() + actuator_increment); - claimed_itfs[1].set_value(claimed_itfs[1].get_value() + system_increment); + claimed_itfs[0].set_value(claimed_itfs[0].get_value().value() + actuator_increment); + claimed_itfs[1].set_value(claimed_itfs[1].get_value().value() + system_increment); // This is needed to account for any missing hits to the read and write cycles as the tests // are going to be run on a non-RT operating system - ASSERT_NEAR(state_itfs[0].get_value(), prev_act_state_value, actuator_increment / 2.0); - ASSERT_NEAR(state_itfs[1].get_value(), prev_system_state_value, system_increment / 2.0); + ASSERT_NEAR( + state_itfs[0].get_value().value(), prev_act_state_value, actuator_increment / 2.0); + ASSERT_NEAR( + state_itfs[1].get_value().value(), prev_system_state_value, system_increment / 2.0); auto [ok_write, failed_hardware_names_write] = rm->write(time, duration); std::this_thread::sleep_for(std::chrono::milliseconds(1)); EXPECT_TRUE(ok_write); diff --git a/hardware_interface_testing/test/test_resource_manager_prepare_perform_switch.cpp b/hardware_interface_testing/test/test_resource_manager_prepare_perform_switch.cpp index d730029d90..db664af74d 100644 --- a/hardware_interface_testing/test/test_resource_manager_prepare_perform_switch.cpp +++ b/hardware_interface_testing/test/test_resource_manager_prepare_perform_switch.cpp @@ -128,47 +128,47 @@ TEST_F( // When TestSystemCommandModes is ACTIVE expect OK EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 1.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 1.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 101.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 101.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 102.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 102.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 202.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 202.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 203.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 203.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->perform_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 303.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 303.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); // When TestActuatorHardware is UNCONFIGURED expect OK EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 303.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 303.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 403.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 403.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 403.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 403.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 503.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 503.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 503.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 503.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->perform_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 603.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 603.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); }; // System : ACTIVE @@ -182,47 +182,47 @@ TEST_F( // When TestSystemCommandModes is ACTIVE expect OK EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 1.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 1.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 1.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 1.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 101.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 101.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 101.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 101.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 102.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 102.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 102.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 102.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 202.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 202.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 202.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 202.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 203.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 203.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 203.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 203.0); EXPECT_FALSE(rm_->perform_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 303.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 303.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 303.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 303.0); // When TestActuatorHardware is INACTIVE expect OK EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 304.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 304.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 304.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 304.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 404.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 404.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 404.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 404.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 405.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 405.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 405.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 405.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 505.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 505.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 505.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 505.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 506.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 506.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 506.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 506.0); EXPECT_FALSE(rm_->perform_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 606.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 606.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 606.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 606.0); }; // System : INACTIVE @@ -236,47 +236,47 @@ TEST_F( // When TestSystemCommandModes is INACTIVE expect OK EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 1.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 1.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 1.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 1.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 101.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 101.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 101.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 101.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 102.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 102.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 102.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 102.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 202.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 202.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 202.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 202.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 203.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 203.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 203.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 203.0); EXPECT_FALSE(rm_->perform_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 303.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 303.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 303.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 303.0); // When TestActuatorHardware is ACTIVE expect OK EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 304.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 304.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 304.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 304.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 404.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 404.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 404.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 404.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 405.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 405.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 405.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 405.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 505.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 505.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 505.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 505.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 506.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 506.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 506.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 506.0); EXPECT_FALSE(rm_->perform_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 606.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 606.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 606.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 606.0); }; // System : UNCONFIGURED @@ -291,47 +291,47 @@ TEST_F( // When TestSystemCommandModes is UNCONFIGURED expect error EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 100.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 100.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 100.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 100.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 200.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 200.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 200.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 200.0); EXPECT_TRUE(rm_->perform_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 300.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 300.0); // When TestActuatorHardware is INACTIVE expect OK EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 301.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 301.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 401.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 401.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 402.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 402.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 502.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 502.0); EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 503.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 503.0); EXPECT_TRUE(rm_->perform_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 603.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 603.0); }; // System : UNCONFIGURED @@ -346,47 +346,47 @@ TEST_F( // When TestSystemCommandModes is UNCONFIGURED expect error EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_system, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(empty_keys, legal_keys_system)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); // When TestActuatorHardware is INACTIVE expect OK EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, empty_keys)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_FALSE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(empty_keys, legal_keys_actuator)); - EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); - EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); + EXPECT_EQ(claimed_system_acceleration_state_->get_value().value(), 0.0); + EXPECT_EQ(claimed_actuator_position_state_->get_value().value(), 0.0); }; int main(int argc, char ** argv) From 9394fd22bb58c9455d9b6cd4ecde495639e4f060 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 18 Feb 2025 22:24:25 +0100 Subject: [PATCH 23/26] Fix introspection for handles with variable references (#2050) --- .../include/hardware_interface/handle.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/hardware_interface/include/hardware_interface/handle.hpp b/hardware_interface/include/hardware_interface/handle.hpp index 53a0e1ee3a..4327191810 100644 --- a/hardware_interface/include/hardware_interface/handle.hpp +++ b/hardware_interface/include/hardware_interface/handle.hpp @@ -257,17 +257,17 @@ class StateInterface : public Handle void registerIntrospection() const { - if (std::holds_alternative(value_)) + if (value_ptr_ || std::holds_alternative(value_)) { std::function f = [this]() - { return value_ptr_ ? *value_ptr_ : std::numeric_limits::quiet_NaN(); }; + { return value_ptr_ ? *value_ptr_ : std::get(value_); }; DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f); } } void unregisterIntrospection() const { - if (std::holds_alternative(value_)) + if (value_ptr_ || std::holds_alternative(value_)) { DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name()); } @@ -302,17 +302,17 @@ class CommandInterface : public Handle void registerIntrospection() const { - if (std::holds_alternative(value_)) + if (value_ptr_ || std::holds_alternative(value_)) { std::function f = [this]() - { return value_ptr_ ? *value_ptr_ : std::numeric_limits::quiet_NaN(); }; + { return value_ptr_ ? *value_ptr_ : std::get(value_); }; DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f); } } void unregisterIntrospection() const { - if (std::holds_alternative(value_)) + if (value_ptr_ || std::holds_alternative(value_)) { DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name()); } From d126642df685dd0e08b47324d3ca5cb5c67f25fc Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 19 Feb 2025 15:50:54 +0100 Subject: [PATCH 24/26] Use new `get_value` API for newly added tests and semantic components (#2055) --- .../semantic_components/gps_sensor.hpp | 28 +++++-- hardware_interface/test/test_handle.cpp | 84 +++++++++---------- 2 files changed, 62 insertions(+), 50 deletions(-) diff --git a/controller_interface/include/semantic_components/gps_sensor.hpp b/controller_interface/include/semantic_components/gps_sensor.hpp index 4abc943115..052acf27a4 100644 --- a/controller_interface/include/semantic_components/gps_sensor.hpp +++ b/controller_interface/include/semantic_components/gps_sensor.hpp @@ -59,7 +59,10 @@ class GPSSensor : public SemanticComponentInterface * * \return Status */ - int8_t get_status() const { return static_cast(state_interfaces_[0].get().get_value()); } + int8_t get_status() const + { + return static_cast(state_interfaces_[0].get().template get_value().value()); + } /** * Return service used by GPS e.g. fix/no_fix @@ -68,7 +71,7 @@ class GPSSensor : public SemanticComponentInterface */ uint16_t get_service() const { - return static_cast(state_interfaces_[1].get().get_value()); + return static_cast(state_interfaces_[1].get().template get_value().value()); } /** @@ -76,21 +79,30 @@ class GPSSensor : public SemanticComponentInterface * * \return Latitude. */ - double get_latitude() const { return state_interfaces_[2].get().get_value(); } + double get_latitude() const + { + return state_interfaces_[2].get().template get_value().value(); + } /** * Return longitude reported by a GPS * * \return Longitude. */ - double get_longitude() const { return state_interfaces_[3].get().get_value(); } + double get_longitude() const + { + return state_interfaces_[3].get().template get_value().value(); + } /** * Return altitude reported by a GPS * * \return Altitude. */ - double get_altitude() const { return state_interfaces_[4].get().get_value(); } + double get_altitude() const + { + return state_interfaces_[4].get().template get_value().value(); + } /** * Return covariance reported by a GPS. @@ -102,9 +114,9 @@ class GPSSensor : public SemanticComponentInterface typename = std::enable_if_t> const std::array & get_covariance() { - covariance_[0] = state_interfaces_[5].get().get_value(); - covariance_[4] = state_interfaces_[6].get().get_value(); - covariance_[8] = state_interfaces_[7].get().get_value(); + covariance_[0] = state_interfaces_[5].get().template get_value().value(); + covariance_[4] = state_interfaces_[6].get().template get_value().value(); + covariance_[8] = state_interfaces_[7].get().template get_value().value(); return covariance_; } diff --git a/hardware_interface/test/test_handle.cpp b/hardware_interface/test/test_handle.cpp index 2f07f71cad..1a35fd836a 100644 --- a/hardware_interface/test/test_handle.cpp +++ b/hardware_interface/test/test_handle.cpp @@ -35,7 +35,7 @@ TEST(TestHandle, command_interface) ASSERT_TRUE(interface.get_value().has_value()); EXPECT_DOUBLE_EQ(interface.get_value().value(), value); EXPECT_DOUBLE_EQ(interface.get_value().value(), value); - EXPECT_NO_THROW(bool status = interface.set_value(0.0)); + EXPECT_NO_THROW({ interface.set_value(0.0); }); ASSERT_TRUE(interface.get_value().has_value()); EXPECT_DOUBLE_EQ(interface.get_value().value(), 0.0); } @@ -70,7 +70,7 @@ TEST(TestHandle, value_methods_work_on_non_nullptr) CommandInterface handle{JOINT_NAME, FOO_INTERFACE, &value}; ASSERT_TRUE(handle.get_value().has_value()); EXPECT_DOUBLE_EQ(handle.get_value().value(), value); - EXPECT_NO_THROW(bool status_set = handle.set_value(0.0)); + EXPECT_NO_THROW({ handle.set_value(0.0); }); ASSERT_TRUE(handle.get_value().has_value()); EXPECT_DOUBLE_EQ(handle.get_value().value(), 0.0); } @@ -109,11 +109,11 @@ TEST(TestHandle, copy_constructor) double value = 1.337; hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value}; hardware_interface::Handle copy(handle); - EXPECT_DOUBLE_EQ(copy.get_value(), value); - EXPECT_DOUBLE_EQ(handle.get_value(), value); - EXPECT_NO_THROW(copy.set_value(0.0)); - EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); - EXPECT_DOUBLE_EQ(handle.get_value(), 0.0); + EXPECT_DOUBLE_EQ(copy.get_value().value(), value); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); + EXPECT_NO_THROW({ copy.set_value(0.0); }); + EXPECT_DOUBLE_EQ(copy.get_value().value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value().value(), 0.0); } { double value = 1.337; @@ -122,20 +122,20 @@ TEST(TestHandle, copy_constructor) info.data_type = "double"; InterfaceDescription itf_descr{JOINT_NAME, info}; hardware_interface::Handle handle{itf_descr}; - EXPECT_TRUE(std::isnan(handle.get_value())); - handle.set_value(value); + EXPECT_TRUE(std::isnan(handle.get_value().value())); + ASSERT_TRUE(handle.set_value(value)); hardware_interface::Handle copy(handle); EXPECT_EQ(copy.get_name(), handle.get_name()); EXPECT_EQ(copy.get_interface_name(), handle.get_interface_name()); EXPECT_EQ(copy.get_prefix_name(), handle.get_prefix_name()); - EXPECT_DOUBLE_EQ(copy.get_value(), value); - EXPECT_DOUBLE_EQ(handle.get_value(), value); - EXPECT_NO_THROW(copy.set_value(0.0)); - EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); - EXPECT_DOUBLE_EQ(handle.get_value(), value); - EXPECT_NO_THROW(copy.set_value(0.52)); - EXPECT_DOUBLE_EQ(copy.get_value(), 0.52); - EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_DOUBLE_EQ(copy.get_value().value(), value); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); + EXPECT_NO_THROW({ copy.set_value(0.0); }); + EXPECT_DOUBLE_EQ(copy.get_value().value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); + EXPECT_NO_THROW({ copy.set_value(0.52); }); + EXPECT_DOUBLE_EQ(copy.get_value().value(), 0.52); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); } } @@ -144,9 +144,9 @@ TEST(TesHandle, move_constructor) double value = 1.337; hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value}; hardware_interface::Handle moved{std::move(handle)}; - EXPECT_DOUBLE_EQ(moved.get_value(), value); - EXPECT_NO_THROW(moved.set_value(0.0)); - EXPECT_DOUBLE_EQ(moved.get_value(), 0.0); + EXPECT_DOUBLE_EQ(moved.get_value().value(), value); + EXPECT_NO_THROW({ moved.set_value(0.0); }); + EXPECT_DOUBLE_EQ(moved.get_value().value(), 0.0); } TEST(TestHandle, copy_assignment) @@ -156,14 +156,14 @@ TEST(TestHandle, copy_assignment) double value_2 = 2.337; hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value_1}; hardware_interface::Handle copy{JOINT_NAME, "random", &value_2}; - EXPECT_DOUBLE_EQ(copy.get_value(), value_2); - EXPECT_DOUBLE_EQ(handle.get_value(), value_1); + EXPECT_DOUBLE_EQ(copy.get_value().value(), value_2); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value_1); copy = handle; - EXPECT_DOUBLE_EQ(copy.get_value(), value_1); - EXPECT_DOUBLE_EQ(handle.get_value(), value_1); - EXPECT_NO_THROW(copy.set_value(0.0)); - EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); - EXPECT_DOUBLE_EQ(handle.get_value(), 0.0); + EXPECT_DOUBLE_EQ(copy.get_value().value(), value_1); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value_1); + EXPECT_NO_THROW({ copy.set_value(0.0); }); + EXPECT_DOUBLE_EQ(copy.get_value().value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value().value(), 0.0); EXPECT_DOUBLE_EQ(value_1, 0.0); EXPECT_DOUBLE_EQ(value_2, 2.337); } @@ -175,20 +175,20 @@ TEST(TestHandle, copy_assignment) info.data_type = "double"; InterfaceDescription itf_descr{JOINT_NAME, info}; hardware_interface::Handle handle{itf_descr}; - EXPECT_TRUE(std::isnan(handle.get_value())); - handle.set_value(value); + EXPECT_TRUE(std::isnan(handle.get_value().value())); + ASSERT_TRUE(handle.set_value(value)); hardware_interface::Handle copy = handle; EXPECT_EQ(copy.get_name(), handle.get_name()); EXPECT_EQ(copy.get_interface_name(), handle.get_interface_name()); EXPECT_EQ(copy.get_prefix_name(), handle.get_prefix_name()); - EXPECT_DOUBLE_EQ(copy.get_value(), value); - EXPECT_DOUBLE_EQ(handle.get_value(), value); - EXPECT_NO_THROW(copy.set_value(0.0)); - EXPECT_DOUBLE_EQ(copy.get_value(), 0.0); - EXPECT_DOUBLE_EQ(handle.get_value(), value); - EXPECT_NO_THROW(copy.set_value(0.52)); - EXPECT_DOUBLE_EQ(copy.get_value(), 0.52); - EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_DOUBLE_EQ(copy.get_value().value(), value); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); + EXPECT_NO_THROW({ copy.set_value(0.0); }); + EXPECT_DOUBLE_EQ(copy.get_value().value(), 0.0); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); + EXPECT_NO_THROW({ copy.set_value(0.52); }); + EXPECT_DOUBLE_EQ(copy.get_value().value(), 0.52); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); } } @@ -198,10 +198,10 @@ TEST(TestHandle, move_assignment) double value_2 = 2.337; hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value}; hardware_interface::Handle moved{JOINT_NAME, "random", &value_2}; - EXPECT_DOUBLE_EQ(moved.get_value(), value_2); - EXPECT_DOUBLE_EQ(handle.get_value(), value); + EXPECT_DOUBLE_EQ(moved.get_value().value(), value_2); + EXPECT_DOUBLE_EQ(handle.get_value().value(), value); moved = std::move(handle); - EXPECT_DOUBLE_EQ(moved.get_value(), value); - EXPECT_NO_THROW(moved.set_value(0.0)); - EXPECT_DOUBLE_EQ(moved.get_value(), 0.0); + EXPECT_DOUBLE_EQ(moved.get_value().value(), value); + EXPECT_NO_THROW({ moved.set_value(0.0); }); + EXPECT_DOUBLE_EQ(moved.get_value().value(), 0.0); } From 29ed1f99226b0af3a73695cae4df7ba4f6b202ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 19 Feb 2025 18:24:07 +0100 Subject: [PATCH 25/26] [CI] 3rd party downstream build: Build the ros2_control packages from source (#2054) --- .../workflows/jazzy-semi-binary-downstream-build.yml | 8 +++++--- .../rolling-semi-binary-downstream-build.yml | 8 +++++--- ros_controls.humble.repos | 12 ++++++++---- ros_controls.jazzy.repos | 8 ++++++++ ros_controls.rolling.repos | 8 ++++++++ 5 files changed, 34 insertions(+), 10 deletions(-) diff --git a/.github/workflows/jazzy-semi-binary-downstream-build.yml b/.github/workflows/jazzy-semi-binary-downstream-build.yml index 3bcf417887..645941ee95 100644 --- a/.github/workflows/jazzy-semi-binary-downstream-build.yml +++ b/.github/workflows/jazzy-semi-binary-downstream-build.yml @@ -30,7 +30,7 @@ jobs: ros_repo: testing ref_for_scheduled_build: master upstream_workspace: ros2_control.jazzy.repos - # we don't test this repository, we just build it + # we don't test target_workspace, we just build it not_test_build: true # we test the downstream packages, which are part of our organization downstream_workspace: ros_controls.jazzy.repos @@ -42,8 +42,10 @@ jobs: ros_repo: testing ref_for_scheduled_build: master upstream_workspace: ros2_control.jazzy.repos - # we don't test this repository, we just build it + # we don't test target_workspace, we just build it not_test_build: true # we don't test the downstream packages, which are outside of our organization - downstream_workspace: downstream.jazzy.repos + downstream_workspace: | # build also the ros_controls packages + ros_controls.jazzy.repos + downstream.jazzy.repos not_test_downstream: true diff --git a/.github/workflows/rolling-semi-binary-downstream-build.yml b/.github/workflows/rolling-semi-binary-downstream-build.yml index 57db2ae7ba..67d22def26 100644 --- a/.github/workflows/rolling-semi-binary-downstream-build.yml +++ b/.github/workflows/rolling-semi-binary-downstream-build.yml @@ -34,7 +34,7 @@ jobs: ros_repo: testing ref_for_scheduled_build: master upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos - # we don't test this repository, we just build it + # we don't test target_workspace, we just build it not_test_build: true # we test the downstream packages, which are part of our organization downstream_workspace: ros_controls.${{ matrix.ROS_DISTRO }}.repos @@ -50,8 +50,10 @@ jobs: ros_repo: testing ref_for_scheduled_build: master upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos - # we don't test this repository, we just build it + # we don't test target_workspace, we just build it not_test_build: true # we don't test the downstream packages, which are outside of our organization - downstream_workspace: downstream.${{ matrix.ROS_DISTRO }}.repos + downstream_workspace: | # build also the ros_controls packages + ros_controls.${{ matrix.ROS_DISTRO }}.repos + downstream.${{ matrix.ROS_DISTRO }}.repos not_test_downstream: true diff --git a/ros_controls.humble.repos b/ros_controls.humble.repos index 8cb447612b..a9ad96bff4 100644 --- a/ros_controls.humble.repos +++ b/ros_controls.humble.repos @@ -1,8 +1,4 @@ repositories: - ros-controls/gazebo_ros2_control: - type: git - url: https://github.com/ros-controls/gazebo_ros2_control.git - version: humble ros-controls/gz_ros2_control: type: git url: https://github.com/ros-controls/gz_ros2_control.git @@ -15,3 +11,11 @@ repositories: type: git url: https://github.com/ros-controls/ros2_controllers.git version: humble + ros-controls/control_toolbox: + type: git + url: https://github.com/ros-controls/control_toolbox.git + version: humble + ros-controls/kinematics_interface: + type: git + url: https://github.com/ros-controls/kinematics_interface.git + version: humble diff --git a/ros_controls.jazzy.repos b/ros_controls.jazzy.repos index d2c3a15743..483de8548c 100644 --- a/ros_controls.jazzy.repos +++ b/ros_controls.jazzy.repos @@ -11,3 +11,11 @@ repositories: type: git url: https://github.com/ros-controls/ros2_controllers.git version: master + ros-controls/control_toolbox: + type: git + url: https://github.com/ros-controls/control_toolbox.git + version: ros2-master + ros-controls/kinematics_interface: + type: git + url: https://github.com/ros-controls/kinematics_interface.git + version: master diff --git a/ros_controls.rolling.repos b/ros_controls.rolling.repos index 45d6fe6040..e13b0f7bba 100644 --- a/ros_controls.rolling.repos +++ b/ros_controls.rolling.repos @@ -11,3 +11,11 @@ repositories: type: git url: https://github.com/ros-controls/ros2_controllers.git version: master + ros-controls/control_toolbox: + type: git + url: https://github.com/ros-controls/control_toolbox.git + version: ros2-master + ros-controls/kinematics_interface: + type: git + url: https://github.com/ros-controls/kinematics_interface.git + version: master From 201d3a7d3ffc59efd911723812609f22bbf45c6e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 19 Feb 2025 18:48:44 +0100 Subject: [PATCH 26/26] [CI] Build the ros2_control packages from source (#2058) --- .github/workflows/humble-semi-binary-downstream-build.yml | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/.github/workflows/humble-semi-binary-downstream-build.yml b/.github/workflows/humble-semi-binary-downstream-build.yml index f0bc3a9fd2..117516b767 100644 --- a/.github/workflows/humble-semi-binary-downstream-build.yml +++ b/.github/workflows/humble-semi-binary-downstream-build.yml @@ -30,7 +30,7 @@ jobs: ros_repo: testing ref_for_scheduled_build: humble upstream_workspace: ros2_control.humble.repos - # we don't test this repository, we just build it + # we don't test target_workspace, we just build it not_test_build: true # we test the downstream packages, which are part of our organization downstream_workspace: ros_controls.humble.repos @@ -42,8 +42,10 @@ jobs: ros_repo: testing ref_for_scheduled_build: humble upstream_workspace: ros2_control.humble.repos - # we don't test this repository, we just build it + # we don't test target_workspace, we just build it not_test_build: true # we don't test the downstream packages, which are outside of our organization - downstream_workspace: downstream.humble.repos + downstream_workspace: | # build also the ros2_control packages + ros_controls.humble.repos + downstream.humble.repos not_test_downstream: true