From a86327758234fe324deb22f01cee3701390056e3 Mon Sep 17 00:00:00 2001 From: Takashi Sato Date: Mon, 24 Jun 2024 11:21:57 +0900 Subject: [PATCH 1/7] add test cases to reveal bugs in the switch_controller --- ...llers_chaining_with_controller_manager.cpp | 140 ++++++++++++++++++ 1 file changed, 140 insertions(+) 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 eadca39756..b47f699240 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -12,6 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#define TEST_BUG1 +#define TEST_BUG2 +#define TEST_BUG3 + #include #include #include @@ -46,6 +50,9 @@ class TestableTestChainableController : public test_chainable_controller::TestCh FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_error_handling); + FRIEND_TEST( + TestControllerChainingWithControllerManager, + test_chained_controllers_activation_error_handling2); FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_switching_error_handling); @@ -80,6 +87,9 @@ class TestableControllerManager : public controller_manager::ControllerManager FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_error_handling); + FRIEND_TEST( + TestControllerChainingWithControllerManager, + test_chained_controllers_activation_error_handling2); FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_switching_error_handling); @@ -775,6 +785,93 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + + // !---- ---- +#ifdef TEST_BUG1 + // Check if the controllers are not in chained mode + ASSERT_FALSE(pid_left_wheel_controller + ->is_in_chained_mode()); // !BUG: should be not in chained mode but is in + ASSERT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); +#endif + // !---- ---- +} + +TEST_P( + TestControllerChainingWithControllerManager, test_chained_controllers_activation_error_handling2) +{ + SetupControllers(); + + // add all controllers - CONTROLLERS HAVE TO ADDED IN EXECUTION ORDER + cm_->add_controller( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller_two, DIFF_DRIVE_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_left_wheel_controller, PID_LEFT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_right_wheel_controller, PID_RIGHT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + + CheckIfControllersAreAddedCorrectly(); + + ConfigureAndCheckControllers(); + + // Set ControllerManager into Debug-Mode output to have detailed output on updating controllers + cm_->get_logger().set_level(rclcpp::Logger::Level::Debug); + rclcpp::get_logger("ControllerManager::utils").set_level(rclcpp::Logger::Level::Debug); + + // at beginning controllers are not in chained mode + EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + + // !---- ---- +#ifdef TEST_BUG2 + // Test Case: Trying to activate a preceding controller and one of the following controller + // --> return error; preceding controller are not activated, + // BUT following controller IS activated + static std::unordered_map expected = { + {controller_manager_msgs::srv::SwitchController::Request::STRICT, + {controller_interface::return_type::ERROR, std::future_status::ready, + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE}}, + {controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT, + {controller_interface::return_type::OK, std::future_status::timeout, + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE}}}; + + // Attempt to activate preceding controllers (position tracking and diff-drive controller) and + // one of the following controller (pid_left_wheel_controller) + switch_test_controllers( + {DIFF_DRIVE_CONTROLLER, PID_LEFT_WHEEL}, {}, test_param.strictness, + expected.at(test_param.strictness).future_status, + expected.at(test_param.strictness).return_type); + + // Preceding controller should stay deactivated and following controller + // should be activated (if BEST_EFFORT) + // If STRICT, preceding controller and following controller should stay deactivated + ASSERT_EQ(expected.at(test_param.strictness).state, pid_left_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + pid_right_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller->get_state().id()); + + // Check if the controllers are not in chained mode + ASSERT_FALSE(pid_left_wheel_controller + ->is_in_chained_mode()); // !BUG: should be not in chained mode but is in + ASSERT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); +#endif + // !---- ---- } TEST_P( @@ -977,6 +1074,49 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + + // !---- ---- +#ifdef TEST_BUG3 + // Test Case: middle preceding/following controller deactivation but the most preceding and the + // lowest following controllers are active + // --> return error; controllers stay in the same state as they were + + // Activate all controllers for this test + ActivateController( + POSITION_TRACKING_CONTROLLER, controller_interface::return_type::OK, + std::future_status::timeout); + + // Expect all controllers to be active + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller->get_state().id()); + + // Attempt to deactivate the middle preceding/following controller + switch_test_controllers( + {}, {DIFF_DRIVE_CONTROLLER}, test_param.strictness, std::future_status::ready, + expected.at(test_param.strictness) + .return_type); // !BUG: If BEST_EFFORT, all controllers should stay the same state as they + // were, but a deadlock may occur during the switch_controller process, + // causing the test to timeout. + + // All controllers should still be active + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller->get_state().id()); +#endif + // !---- ---- } TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order) From df56d4f9bffbf87cf846fbf805b83763d543699e Mon Sep 17 00:00:00 2001 From: Takashi Sato Date: Mon, 24 Jun 2024 11:24:57 +0900 Subject: [PATCH 2/7] to fix the bug in switch_controller, modify the process to retry the check from the beginning whenever there is a change in the (de)activate request (but use goto) --- controller_manager/src/controller_manager.cpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 3b84fc07e4..00137860e2 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -963,6 +963,16 @@ controller_interface::return_type ControllerManager::switch_controller( const std::vector & controllers = rt_controllers_wrapper_.get_updated_list(guard); +LABEL_CHECK_REQUEST: + // Set these interfaces as unavailable when clearing requests to avoid leaving them in available + // state without the controller being in active state + for (const auto & controller_name : to_chained_mode_request_) + { + resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); + } + to_chained_mode_request_.clear(); + from_chained_mode_request_.clear(); + // if a preceding controller is deactivated, all first-level controllers should be switched 'from' // chained mode propagate_deactivation_of_chained_mode(controllers); @@ -1006,7 +1016,7 @@ controller_interface::return_type ControllerManager::switch_controller( // remove controller that can not be activated from the activation request and step-back // iterator to correctly step to the next element in the list in the loop activate_request_.erase(ctrl_it); - --ctrl_it; + goto LABEL_CHECK_REQUEST; } if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) { @@ -1052,7 +1062,7 @@ controller_interface::return_type ControllerManager::switch_controller( // remove controller that can not be activated from the activation request and step-back // iterator to correctly step to the next element in the list in the loop deactivate_request_.erase(ctrl_it); - --ctrl_it; + goto LABEL_CHECK_REQUEST; } if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) { From fcc1b966890b1474013460552ea6d6626c0a69d2 Mon Sep 17 00:00:00 2001 From: Takashi Sato Date: Mon, 24 Jun 2024 11:26:27 +0900 Subject: [PATCH 3/7] change the bug fix implementation to not use goto --- controller_manager/src/controller_manager.cpp | 222 +++++++++++------- 1 file changed, 132 insertions(+), 90 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 00137860e2..c4efe9ed95 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -963,115 +963,157 @@ controller_interface::return_type ControllerManager::switch_controller( const std::vector & controllers = rt_controllers_wrapper_.get_updated_list(guard); -LABEL_CHECK_REQUEST: - // Set these interfaces as unavailable when clearing requests to avoid leaving them in available - // state without the controller being in active state - for (const auto & controller_name : to_chained_mode_request_) + enum class CreateRequestResult { - resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); - } - to_chained_mode_request_.clear(); - from_chained_mode_request_.clear(); - - // if a preceding controller is deactivated, all first-level controllers should be switched 'from' - // chained mode - propagate_deactivation_of_chained_mode(controllers); + OK, + ERROR, + RETRY + }; - // check if controllers should be switched 'to' chained mode when controllers are activated - for (auto ctrl_it = activate_request_.begin(); ctrl_it != activate_request_.end(); ++ctrl_it) + const auto check_de_activate_request_and_create_chained_mode_request = + [this, &strictness, &controllers]() -> CreateRequestResult { - auto controller_it = std::find_if( - controllers.begin(), controllers.end(), - std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); - controller_interface::return_type status = controller_interface::return_type::OK; - - // if controller is not inactive then do not do any following-controllers checks - if (!is_controller_inactive(controller_it->c)) + const auto clear_chained_mode_requests = [this]() { - RCLCPP_WARN( - get_logger(), - "Controller with name '%s' is not inactive so its following " - "controllers do not have to be checked, because it cannot be activated.", - controller_it->info.name.c_str()); - status = controller_interface::return_type::ERROR; - } - else - { - status = check_following_controllers_for_activate(controllers, strictness, controller_it); - } + // Set these interfaces as unavailable when clearing requests to avoid leaving them in + // available state without the controller being in active state + for (const auto & controller_name : to_chained_mode_request_) + { + resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); + } + to_chained_mode_request_.clear(); + from_chained_mode_request_.clear(); + }; + + // if a preceding controller is deactivated, all first-level controllers should be switched + // 'from' chained mode + propagate_deactivation_of_chained_mode(controllers); - if (status != controller_interface::return_type::OK) + // check if controllers should be switched 'to' chained mode when controllers are activated + for (auto ctrl_it = activate_request_.begin(); ctrl_it != activate_request_.end(); ++ctrl_it) { - RCLCPP_WARN( - get_logger(), - "Could not activate controller with name '%s'. Check above warnings for more details. " - "Check the state of the controllers and their required interfaces using " - "`ros2 control list_controllers -v` CLI to get more information.", - (*ctrl_it).c_str()); - if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + auto controller_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); + controller_interface::return_type status = controller_interface::return_type::OK; + + // if controller is not inactive then do not do any following-controllers checks + if (!is_controller_inactive(controller_it->c)) { - // TODO(destogl): automatic manipulation of the chain: - // || strictness == - // controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN); - // remove controller that can not be activated from the activation request and step-back - // iterator to correctly step to the next element in the list in the loop - activate_request_.erase(ctrl_it); - goto LABEL_CHECK_REQUEST; + RCLCPP_WARN( + get_logger(), + "Controller with name '%s' is not inactive so its following " + "controllers do not have to be checked, because it cannot be activated.", + controller_it->info.name.c_str()); + status = controller_interface::return_type::ERROR; } - if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + else { - RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); - // reset all lists - clear_requests(); - return controller_interface::return_type::ERROR; + status = check_following_controllers_for_activate(controllers, strictness, controller_it); } - } - } - - // check if controllers should be deactivated if used in chained mode - for (auto ctrl_it = deactivate_request_.begin(); ctrl_it != deactivate_request_.end(); ++ctrl_it) - { - auto controller_it = std::find_if( - controllers.begin(), controllers.end(), - std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); - controller_interface::return_type status = controller_interface::return_type::OK; - // if controller is not active then skip preceding-controllers checks - if (!is_controller_active(controller_it->c)) - { - RCLCPP_WARN( - get_logger(), "Controller with name '%s' can not be deactivated since it is not active.", - controller_it->info.name.c_str()); - status = controller_interface::return_type::ERROR; - } - else - { - status = check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it); + if (status != controller_interface::return_type::OK) + { + RCLCPP_WARN( + get_logger(), + "Could not activate controller with name '%s'. Check above warnings for more details. " + "Check the state of the controllers and their required interfaces using " + "`ros2 control list_controllers -v` CLI to get more information.", + (*ctrl_it).c_str()); + if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + { + // TODO(destogl): automatic manipulation of the chain: + // || strictness == + // controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN); + // remove controller that can not be activated from the activation request and step-back + // iterator to correctly step to the next element in the list in the loop + activate_request_.erase(ctrl_it); + // reset chained mode request lists and will retry the creation of the request + clear_chained_mode_requests(); + return CreateRequestResult::RETRY; + } + if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + { + RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); + // reset all lists + clear_requests(); + return CreateRequestResult::ERROR; + } + } } - if (status != controller_interface::return_type::OK) + // check if controllers should be deactivated if used in chained mode + for (auto ctrl_it = deactivate_request_.begin(); ctrl_it != deactivate_request_.end(); + ++ctrl_it) { - RCLCPP_WARN( - get_logger(), - "Could not deactivate controller with name '%s'. Check above warnings for more details. " - "Check the state of the controllers and their required interfaces using " - "`ros2 control list_controllers -v` CLI to get more information.", - (*ctrl_it).c_str()); - if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + auto controller_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); + controller_interface::return_type status = controller_interface::return_type::OK; + + // if controller is not active then skip preceding-controllers checks + if (!is_controller_active(controller_it->c)) { - // remove controller that can not be activated from the activation request and step-back - // iterator to correctly step to the next element in the list in the loop - deactivate_request_.erase(ctrl_it); - goto LABEL_CHECK_REQUEST; + RCLCPP_WARN( + get_logger(), "Controller with name '%s' can not be deactivated since it is not active.", + controller_it->info.name.c_str()); + status = controller_interface::return_type::ERROR; } - if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + else { - RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); - // reset all lists - clear_requests(); - return controller_interface::return_type::ERROR; + status = + check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it); } + + if (status != controller_interface::return_type::OK) + { + RCLCPP_WARN( + get_logger(), + "Could not deactivate controller with name '%s'. Check above warnings for more details. " + "Check the state of the controllers and their required interfaces using " + "`ros2 control list_controllers -v` CLI to get more information.", + (*ctrl_it).c_str()); + if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + { + // remove controller that can not be activated from the activation request and step-back + // iterator to correctly step to the next element in the list in the loop + deactivate_request_.erase(ctrl_it); + // reset chained mode request lists and will retry the creation of the request + clear_chained_mode_requests(); + return CreateRequestResult::RETRY; + } + if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + { + RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); + // reset all lists + clear_requests(); + return CreateRequestResult::ERROR; + } + } + } + + return CreateRequestResult::OK; + }; + + // Validate the (de)activate request and create from/to chained mode requests as needed. + // If the strictness value is STRICT, return an error for any invalid request. + // If the strictness value is BEST_EFFORT, remove any controllers that cannot be + // (de)activated from the request and proceed. However, any changes to the + // (de)activate request will affect the outcome of the check and creation process, + // so retry from the beginning. + while (true) + { + const auto result = check_de_activate_request_and_create_chained_mode_request(); + if (result == CreateRequestResult::RETRY) + { + continue; + } + if (result == CreateRequestResult::ERROR) + { + return controller_interface::return_type::ERROR; } + // if result == CreateRequestResult::OK -> break the loop + break; } for (const auto & controller : controllers) From 005a79fb7b961d3237e1b02b3edf0521ed866b61 Mon Sep 17 00:00:00 2001 From: Takashi Sato Date: Wed, 26 Jun 2024 15:43:39 +0900 Subject: [PATCH 4/7] remove TEST_BUG definition --- ...llers_chaining_with_controller_manager.cpp | 27 +++---------------- 1 file changed, 3 insertions(+), 24 deletions(-) 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 b47f699240..e7517a0335 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -12,10 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -#define TEST_BUG1 -#define TEST_BUG2 -#define TEST_BUG3 - #include #include #include @@ -786,15 +782,10 @@ TEST_P( ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); - // !---- ---- -#ifdef TEST_BUG1 // Check if the controllers are not in chained mode - ASSERT_FALSE(pid_left_wheel_controller - ->is_in_chained_mode()); // !BUG: should be not in chained mode but is in + ASSERT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); -#endif - // !---- ---- } TEST_P( @@ -832,8 +823,6 @@ TEST_P( EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); - // !---- ---- -#ifdef TEST_BUG2 // Test Case: Trying to activate a preceding controller and one of the following controller // --> return error; preceding controller are not activated, // BUT following controller IS activated @@ -866,12 +855,9 @@ TEST_P( position_tracking_controller->get_state().id()); // Check if the controllers are not in chained mode - ASSERT_FALSE(pid_left_wheel_controller - ->is_in_chained_mode()); // !BUG: should be not in chained mode but is in + ASSERT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); -#endif - // !---- ---- } TEST_P( @@ -1075,8 +1061,6 @@ TEST_P( ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); - // !---- ---- -#ifdef TEST_BUG3 // Test Case: middle preceding/following controller deactivation but the most preceding and the // lowest following controllers are active // --> return error; controllers stay in the same state as they were @@ -1100,10 +1084,7 @@ TEST_P( // Attempt to deactivate the middle preceding/following controller switch_test_controllers( {}, {DIFF_DRIVE_CONTROLLER}, test_param.strictness, std::future_status::ready, - expected.at(test_param.strictness) - .return_type); // !BUG: If BEST_EFFORT, all controllers should stay the same state as they - // were, but a deadlock may occur during the switch_controller process, - // causing the test to timeout. + expected.at(test_param.strictness).return_type); // All controllers should still be active ASSERT_EQ( @@ -1115,8 +1096,6 @@ TEST_P( ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, position_tracking_controller->get_state().id()); -#endif - // !---- ---- } TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order) From f41a52f643dca8b5a34c6708b19b718a0d267bd5 Mon Sep 17 00:00:00 2001 From: Takashi Sato Date: Fri, 5 Jul 2024 21:40:43 +0900 Subject: [PATCH 5/7] merge master and fix conflict --- .github/workflows/rosdoc2.yml | 14 + .pre-commit-config.yaml | 9 +- controller_interface/CHANGELOG.rst | 3 + .../chainable_controller_interface.hpp | 26 +- .../controller_interface.hpp | 8 + .../controller_interface_base.hpp | 13 +- controller_interface/package.xml | 2 +- .../src/chainable_controller_interface.cpp | 65 +- .../src/controller_interface.cpp | 5 + .../test_chainable_controller_interface.cpp | 47 +- .../test_chainable_controller_interface.hpp | 27 +- controller_manager/CHANGELOG.rst | 8 + .../doc/controller_chaining.rst | 47 +- .../doc/images/chaining_example2.png | Bin 37092 -> 89572 bytes .../doc/images/rqt_controller_manager.png | Bin 0 -> 49114 bytes controller_manager/doc/userdoc.rst | 15 + .../controller_manager/controller_manager.hpp | 22 +- controller_manager/package.xml | 2 +- controller_manager/src/controller_manager.cpp | 243 +- .../test_chainable_controller.cpp | 60 + .../test_chainable_controller.hpp | 16 + .../test/test_controller/test_controller.cpp | 10 + .../test/test_controller/test_controller.hpp | 3 + .../test/test_controller_manager_srvs.cpp | 123 +- .../test_controller_manager_urdf_passing.cpp | 39 +- ...llers_chaining_with_controller_manager.cpp | 946 +++++- controller_manager_msgs/CHANGELOG.rst | 3 + .../msg/ControllerState.msg | 1 + controller_manager_msgs/package.xml | 2 +- doc/Doxyfile | 2579 ----------------- doc/release_notes/Jazzy.rst | 3 + hardware_interface/CHANGELOG.rst | 11 + hardware_interface/CMakeLists.txt | 1 + .../hardware_interface/resource_manager.hpp | 108 +- hardware_interface/package.xml | 2 +- hardware_interface/src/component_parser.cpp | 105 +- hardware_interface/src/resource_manager.cpp | 301 +- .../mock_components/test_generic_system.cpp | 5 +- .../test/test_component_parser.cpp | 29 - .../test_hardware_components.xml | 6 + .../test_imu_sensor.cpp | 142 + hardware_interface_testing/CHANGELOG.rst | 5 + hardware_interface_testing/package.xml | 2 +- .../test/test_components/test_actuator.cpp | 5 + .../test/test_components/test_sensor.cpp | 2 +- .../test/test_components/test_system.cpp | 16 + .../test/test_resource_manager.cpp | 125 +- .../test/test_resource_manager.hpp | 7 +- joint_limits/CHANGELOG.rst | 6 + joint_limits/CMakeLists.txt | 55 +- .../joint_limits/joint_limiter_interface.hpp | 250 ++ .../joint_limits/joint_limits_rosparam.hpp | 302 +- .../joint_limits/joint_saturation_limiter.hpp | 105 + .../include/joint_limits/visibility_control.h | 49 + joint_limits/joint_limiters.xml | 11 + joint_limits/package.xml | 14 +- joint_limits/src/joint_limiter_interface.cpp | 21 + joint_limits/src/joint_saturation_limiter.cpp | 478 +++ .../test/joint_saturation_limiter_param.yaml | 57 + .../test/test_joint_saturation_limiter.cpp | 569 ++++ .../test/test_joint_saturation_limiter.hpp | 107 + ros2_control/CHANGELOG.rst | 5 + ros2_control/doc/conf.py | 5 + ros2_control/doc/index.rst | 32 + ros2_control/package.xml | 5 +- ros2_control/rosdoc2.yaml | 20 + ros2_control_test_assets/CHANGELOG.rst | 6 + .../ros2_control_test_assets/descriptions.hpp | 462 ++- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 3 + ros2controlcli/package.xml | 7 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 5 + rqt_controller_manager/package.xml | 7 +- .../resource/controller_manager.ui | 36 +- .../{controller_info.ui => popup_info.ui} | 3 - .../controller_manager.py | 305 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 3 + transmission_interface/package.xml | 2 +- 80 files changed, 4905 insertions(+), 3244 deletions(-) create mode 100644 .github/workflows/rosdoc2.yml create mode 100644 controller_manager/doc/images/rqt_controller_manager.png delete mode 100644 doc/Doxyfile create mode 100644 hardware_interface/test/test_hardware_components/test_imu_sensor.cpp create mode 100644 joint_limits/include/joint_limits/joint_limiter_interface.hpp create mode 100644 joint_limits/include/joint_limits/joint_saturation_limiter.hpp create mode 100644 joint_limits/include/joint_limits/visibility_control.h create mode 100644 joint_limits/joint_limiters.xml create mode 100644 joint_limits/src/joint_limiter_interface.cpp create mode 100644 joint_limits/src/joint_saturation_limiter.cpp create mode 100644 joint_limits/test/joint_saturation_limiter_param.yaml create mode 100644 joint_limits/test/test_joint_saturation_limiter.cpp create mode 100644 joint_limits/test/test_joint_saturation_limiter.hpp create mode 100644 ros2_control/doc/conf.py create mode 100644 ros2_control/doc/index.rst create mode 100644 ros2_control/rosdoc2.yaml rename rqt_controller_manager/resource/{controller_info.ui => popup_info.ui} (96%) diff --git a/.github/workflows/rosdoc2.yml b/.github/workflows/rosdoc2.yml new file mode 100644 index 0000000000..07a9e2904a --- /dev/null +++ b/.github/workflows/rosdoc2.yml @@ -0,0 +1,14 @@ +name: rosdoc2 + +on: + workflow_dispatch: + pull_request: + paths: + - ros2_control/doc/** + - ros2_control/rosdoc2.yaml + - ros2_control/package.xml + + +jobs: + check: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rosdoc2.yml@master diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 8e604b2f7f..29862f70e4 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -26,6 +26,7 @@ repos: - id: check-symlinks - id: check-xml - id: check-yaml + args: ["--allow-multiple-documents"] - id: debug-statements - id: end-of-file-fixer - id: mixed-line-ending @@ -36,7 +37,7 @@ repos: # Python hooks - repo: https://github.com/asottile/pyupgrade - rev: v3.15.2 + rev: v3.16.0 hooks: - id: pyupgrade args: [--py36-plus] @@ -55,14 +56,14 @@ repos: args: ["--line-length=99"] - repo: https://github.com/pycqa/flake8 - rev: 7.0.0 + rev: 7.1.0 hooks: - id: flake8 args: ["--extend-ignore=E501"] # CPP hooks - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v18.1.5 + rev: v18.1.8 hooks: - id: clang-format args: ['-fallback-style=none', '-i'] @@ -132,7 +133,7 @@ repos: exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$ - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.28.4 + rev: 0.28.6 hooks: - id: check-github-workflows args: ["--verbose"] diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index 8d77f4203f..0ab0d31ec4 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.12.0 (2024-07-01) +------------------- + 4.11.0 (2024-05-14) ------------------- * Fix dependencies for source build (`#1533 `_) diff --git a/controller_interface/include/controller_interface/chainable_controller_interface.hpp b/controller_interface/include/controller_interface/chainable_controller_interface.hpp index 2bdccefdc5..2e39f038b1 100644 --- a/controller_interface/include/controller_interface/chainable_controller_interface.hpp +++ b/controller_interface/include/controller_interface/chainable_controller_interface.hpp @@ -15,6 +15,7 @@ #ifndef CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_ #define CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_ +#include #include #include "controller_interface/controller_interface_base.hpp" @@ -55,6 +56,9 @@ class ChainableControllerInterface : public ControllerInterfaceBase CONTROLLER_INTERFACE_PUBLIC bool is_chainable() const final; + CONTROLLER_INTERFACE_PUBLIC + std::vector export_state_interfaces() final; + CONTROLLER_INTERFACE_PUBLIC std::vector export_reference_interfaces() final; @@ -65,8 +69,19 @@ class ChainableControllerInterface : public ControllerInterfaceBase bool is_in_chained_mode() const final; protected: - /// Virtual method that each chainable controller should implement to export its chainable - /// interfaces. + /// Virtual method that each chainable controller should implement to export its read-only + /// chainable interfaces. + /** + * Each chainable controller implements this methods where all its state(read only) interfaces are + * exported. The method has the same meaning as `export_state_interfaces` method from + * hardware_interface::SystemInterface or hardware_interface::ActuatorInterface. + * + * \returns list of StateInterfaces that other controller can use as their inputs. + */ + virtual std::vector on_export_state_interfaces(); + + /// Virtual method that each chainable controller should implement to export its read/write + /// chainable interfaces. /** * Each chainable controller implements this methods where all input (command) interfaces are * exported. The method has the same meaning as `export_command_interface` method from @@ -74,7 +89,7 @@ class ChainableControllerInterface : public ControllerInterfaceBase * * \returns list of CommandInterfaces that other controller can use as their outputs. */ - virtual std::vector on_export_reference_interfaces() = 0; + virtual std::vector on_export_reference_interfaces(); /// Virtual method that each chainable controller should implement to switch chained mode. /** @@ -114,7 +129,12 @@ class ChainableControllerInterface : public ControllerInterfaceBase virtual return_type update_and_write_commands( const rclcpp::Time & time, const rclcpp::Duration & period) = 0; + /// Storage of values for state interfaces + std::vector exported_state_interface_names_; + std::vector state_interfaces_values_; + /// Storage of values for reference interfaces + std::vector exported_reference_interface_names_; std::vector reference_interfaces_; private: diff --git a/controller_interface/include/controller_interface/controller_interface.hpp b/controller_interface/include/controller_interface/controller_interface.hpp index a3d006755f..17f39c8478 100644 --- a/controller_interface/include/controller_interface/controller_interface.hpp +++ b/controller_interface/include/controller_interface/controller_interface.hpp @@ -42,6 +42,14 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase CONTROLLER_INTERFACE_PUBLIC bool is_chainable() const final; + /** + * A non-chainable controller doesn't export any state interfaces. + * + * \returns empty list. + */ + CONTROLLER_INTERFACE_PUBLIC + std::vector export_state_interfaces() final; + /** * Controller has no reference interfaces. * diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index 1c09f71e98..1b5fd2e059 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -224,11 +224,20 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy CONTROLLER_INTERFACE_PUBLIC virtual std::vector export_reference_interfaces() = 0; + /** + * Export interfaces for a chainable controller that can be used as state interface by other + * controllers. + * + * \returns list of state interfaces for preceding controllers. + */ + CONTROLLER_INTERFACE_PUBLIC + virtual std::vector export_state_interfaces() = 0; + /** * Set chained mode of a chainable controller. This method triggers internal processes to switch * a chainable controller to "chained" mode and vice-versa. Setting controller to "chained" mode - * usually involves disabling of subscribers and other external interfaces to avoid potential - * concurrency in input commands. + * usually involves the usage of the controller's reference interfaces by the other + * controllers * * \returns true if mode is switched successfully and false if not. */ diff --git a/controller_interface/package.xml b/controller_interface/package.xml index 9a99449043..00af8a2c9e 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.11.0 + 4.12.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_interface/src/chainable_controller_interface.cpp b/controller_interface/src/chainable_controller_interface.cpp index 2f7c67741e..9f4a171ec3 100644 --- a/controller_interface/src/chainable_controller_interface.cpp +++ b/controller_interface/src/chainable_controller_interface.cpp @@ -44,26 +44,35 @@ return_type ChainableControllerInterface::update( return ret; } -std::vector -ChainableControllerInterface::export_reference_interfaces() +std::vector +ChainableControllerInterface::export_state_interfaces() { - auto reference_interfaces = on_export_reference_interfaces(); + auto state_interfaces = on_export_state_interfaces(); - // check if the "reference_interfaces_" variable is resized to number of interfaces - if (reference_interfaces_.size() != reference_interfaces.size()) + // check if the names of the controller state interfaces begin with the controller's name + for (const auto & interface : state_interfaces) { - // TODO(destogl): Should here be "FATAL"? It is fatal in terms of controller but not for the - // framework - RCLCPP_FATAL( - get_node()->get_logger(), - "The internal storage for reference values 'reference_interfaces_' variable has size '%zu', " - "but it is expected to have the size '%zu' equal to the number of exported reference " - "interfaces. No reference interface will be exported. Please correct and recompile " - "the controller with name '%s' and try again.", - reference_interfaces_.size(), reference_interfaces.size(), get_node()->get_name()); - reference_interfaces.clear(); + if (interface.get_prefix_name() != get_node()->get_name()) + { + RCLCPP_FATAL( + get_node()->get_logger(), + "The name of the interface '%s' does not begin with the controller's name. This is " + "mandatory for state interfaces. No state interface will be exported. Please " + "correct and recompile the controller with name '%s' and try again.", + interface.get_name().c_str(), get_node()->get_name()); + state_interfaces.clear(); + break; + } } + return state_interfaces; +} + +std::vector +ChainableControllerInterface::export_reference_interfaces() +{ + auto reference_interfaces = on_export_reference_interfaces(); + // check if the names of the reference interfaces begin with the controller's name for (const auto & interface : reference_interfaces) { @@ -113,4 +122,30 @@ bool ChainableControllerInterface::is_in_chained_mode() const { return in_chaine bool ChainableControllerInterface::on_set_chained_mode(bool /*chained_mode*/) { return true; } +std::vector +ChainableControllerInterface::on_export_state_interfaces() +{ + state_interfaces_values_.resize(exported_state_interface_names_.size(), 0.0); + std::vector state_interfaces; + for (size_t i = 0; i < exported_state_interface_names_.size(); ++i) + { + state_interfaces.emplace_back(hardware_interface::StateInterface( + get_node()->get_name(), exported_state_interface_names_[i], &state_interfaces_values_[i])); + } + return state_interfaces; +} + +std::vector +ChainableControllerInterface::on_export_reference_interfaces() +{ + reference_interfaces_.resize(exported_reference_interface_names_.size(), 0.0); + std::vector reference_interfaces; + for (size_t i = 0; i < exported_reference_interface_names_.size(); ++i) + { + reference_interfaces.emplace_back(hardware_interface::CommandInterface( + get_node()->get_name(), exported_reference_interface_names_[i], &reference_interfaces_[i])); + } + return reference_interfaces; +} + } // namespace controller_interface diff --git a/controller_interface/src/controller_interface.cpp b/controller_interface/src/controller_interface.cpp index 392a48ffa4..0f11bba71c 100644 --- a/controller_interface/src/controller_interface.cpp +++ b/controller_interface/src/controller_interface.cpp @@ -28,6 +28,11 @@ ControllerInterface::ControllerInterface() : ControllerInterfaceBase() {} bool ControllerInterface::is_chainable() const { return false; } +std::vector ControllerInterface::export_state_interfaces() +{ + return {}; +} + std::vector ControllerInterface::export_reference_interfaces() { return {}; diff --git a/controller_interface/test/test_chainable_controller_interface.cpp b/controller_interface/test/test_chainable_controller_interface.cpp index 47487e019c..2f04273f3e 100644 --- a/controller_interface/test/test_chainable_controller_interface.cpp +++ b/controller_interface/test/test_chainable_controller_interface.cpp @@ -16,6 +16,9 @@ #include +using ::testing::IsEmpty; +using ::testing::SizeIs; + TEST_F(ChainableControllerInterfaceTest, default_returns) { TestableChainableControllerInterface controller; @@ -31,7 +34,7 @@ TEST_F(ChainableControllerInterfaceTest, default_returns) EXPECT_FALSE(controller.is_in_chained_mode()); } -TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces) +TEST_F(ChainableControllerInterfaceTest, export_state_interfaces) { TestableChainableControllerInterface controller; @@ -42,16 +45,16 @@ TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces) controller_interface::return_type::OK); ASSERT_NO_THROW(controller.get_node()); - auto reference_interfaces = controller.export_reference_interfaces(); + auto exported_state_interfaces = controller.export_state_interfaces(); - ASSERT_EQ(reference_interfaces.size(), 1u); - EXPECT_EQ(reference_interfaces[0].get_prefix_name(), TEST_CONTROLLER_NAME); - EXPECT_EQ(reference_interfaces[0].get_interface_name(), "test_itf"); + ASSERT_THAT(exported_state_interfaces, SizeIs(1)); + 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(reference_interfaces[0].get_value(), INTERFACE_VALUE); + EXPECT_EQ(exported_state_interfaces[0].get_value(), EXPORTED_STATE_INTERFACE_VALUE); } -TEST_F(ChainableControllerInterfaceTest, reference_interfaces_storage_not_correct_size) +TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces) { TestableChainableControllerInterface controller; @@ -62,13 +65,16 @@ TEST_F(ChainableControllerInterfaceTest, reference_interfaces_storage_not_correc controller_interface::return_type::OK); ASSERT_NO_THROW(controller.get_node()); - // expect empty return because storage is not resized - controller.reference_interfaces_.clear(); auto reference_interfaces = controller.export_reference_interfaces(); - ASSERT_TRUE(reference_interfaces.empty()); + + ASSERT_THAT(reference_interfaces, SizeIs(1)); + 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); } -TEST_F(ChainableControllerInterfaceTest, reference_interfaces_prefix_is_not_node_name) +TEST_F(ChainableControllerInterfaceTest, interfaces_prefix_is_not_node_name) { TestableChainableControllerInterface controller; @@ -83,7 +89,10 @@ TEST_F(ChainableControllerInterfaceTest, reference_interfaces_prefix_is_not_node // expect empty return because interface prefix is not equal to the node name auto reference_interfaces = controller.export_reference_interfaces(); - ASSERT_TRUE(reference_interfaces.empty()); + ASSERT_THAT(reference_interfaces, IsEmpty()); + // expect empty return because interface prefix is not equal to the node name + auto exported_state_interfaces = controller.export_state_interfaces(); + ASSERT_THAT(exported_state_interfaces, IsEmpty()); } TEST_F(ChainableControllerInterfaceTest, setting_chained_mode) @@ -98,12 +107,15 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode) ASSERT_NO_THROW(controller.get_node()); auto reference_interfaces = controller.export_reference_interfaces(); - ASSERT_EQ(reference_interfaces.size(), 1u); + ASSERT_THAT(reference_interfaces, SizeIs(1)); + auto exported_state_interfaces = controller.export_state_interfaces(); + ASSERT_THAT(exported_state_interfaces, SizeIs(1)); EXPECT_FALSE(controller.is_in_chained_mode()); // Fail setting chained mode EXPECT_EQ(reference_interfaces[0].get_value(), INTERFACE_VALUE); + EXPECT_EQ(exported_state_interfaces[0].get_value(), EXPORTED_STATE_INTERFACE_VALUE); EXPECT_FALSE(controller.set_chained_mode(true)); EXPECT_FALSE(controller.is_in_chained_mode()); @@ -116,6 +128,7 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode) 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); controller.configure(); EXPECT_TRUE(controller.set_chained_mode(false)); @@ -147,6 +160,7 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic) controller_interface::return_type::OK); ASSERT_NO_THROW(controller.get_node()); + EXPECT_FALSE(controller.set_chained_mode(false)); EXPECT_FALSE(controller.is_in_chained_mode()); // call update and update it from subscriber because not in chained mode @@ -154,6 +168,7 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic) controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_INITIAL_REF - 1); + ASSERT_EQ(controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE + 1); // Provoke error in update from subscribers - return ERROR and update_and_write_commands not exec. controller.set_new_reference_interface_value(INTERFACE_VALUE_SUBSCRIBER_ERROR); @@ -161,6 +176,7 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic) controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::ERROR); ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_INITIAL_REF - 1); + ASSERT_EQ(controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE + 1); // Provoke error from update - return ERROR, but reference interface is updated and not reduced controller.set_new_reference_interface_value(INTERFACE_VALUE_UPDATE_ERROR); @@ -168,6 +184,7 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic) controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::ERROR); ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_UPDATE_ERROR); + ASSERT_EQ(controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE + 1); controller.reference_interfaces_[0] = 0.0; @@ -181,6 +198,8 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic) controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); ASSERT_EQ(controller.reference_interfaces_[0], -1.0); + ASSERT_EQ( + controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE + 1); // Provoke error from update - return ERROR, but reference interface is updated directly controller.set_new_reference_interface_value(INTERFACE_VALUE_SUBSCRIBER_ERROR); @@ -189,4 +208,6 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic) controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::ERROR); ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_UPDATE_ERROR); + ASSERT_EQ( + controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE + 1); } diff --git a/controller_interface/test/test_chainable_controller_interface.hpp b/controller_interface/test/test_chainable_controller_interface.hpp index 28401f13d5..f9684c27fd 100644 --- a/controller_interface/test/test_chainable_controller_interface.hpp +++ b/controller_interface/test/test_chainable_controller_interface.hpp @@ -29,24 +29,28 @@ constexpr double INTERFACE_VALUE = 1989.0; constexpr double INTERFACE_VALUE_SUBSCRIBER_ERROR = 12345.0; constexpr double INTERFACE_VALUE_UPDATE_ERROR = 67890.0; constexpr double INTERFACE_VALUE_INITIAL_REF = 1984.0; +constexpr double EXPORTED_STATE_INTERFACE_VALUE = 21833.0; +constexpr double EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE = 82802.0; class TestableChainableControllerInterface : public controller_interface::ChainableControllerInterface { public: - FRIEND_TEST(ChainableControllerInterfaceTest, reference_interfaces_storage_not_correct_size); + FRIEND_TEST(ChainableControllerInterfaceTest, interfaces_storage_not_correct_size); FRIEND_TEST(ChainableControllerInterfaceTest, test_update_logic); TestableChainableControllerInterface() { reference_interfaces_.reserve(1); reference_interfaces_.push_back(INTERFACE_VALUE); + state_interfaces_values_.reserve(1); + state_interfaces_values_.push_back(EXPORTED_STATE_INTERFACE_VALUE); } controller_interface::CallbackReturn on_init() override { // set default value - name_prefix_of_reference_interfaces_ = get_node()->get_name(); + name_prefix_of_interfaces_ = get_node()->get_name(); return controller_interface::CallbackReturn::SUCCESS; } @@ -63,13 +67,24 @@ class TestableChainableControllerInterface controller_interface::interface_configuration_type::NONE}; } + // Implementation of ChainableController virtual methods + std::vector on_export_state_interfaces() override + { + std::vector state_interfaces; + + state_interfaces.push_back(hardware_interface::StateInterface( + name_prefix_of_interfaces_, "test_state", &state_interfaces_values_[0])); + + return state_interfaces; + } + // Implementation of ChainableController virtual methods std::vector on_export_reference_interfaces() override { std::vector command_interfaces; command_interfaces.push_back(hardware_interface::CommandInterface( - name_prefix_of_reference_interfaces_, "test_itf", &reference_interfaces_[0])); + name_prefix_of_interfaces_, "test_itf", &reference_interfaces_[0])); return command_interfaces; } @@ -78,6 +93,7 @@ class TestableChainableControllerInterface { if (reference_interfaces_[0] == 0.0) { + state_interfaces_values_[0] = EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE; return true; } else @@ -107,13 +123,14 @@ class TestableChainableControllerInterface } reference_interfaces_[0] -= 1; + state_interfaces_values_[0] += 1; return controller_interface::return_type::OK; } void set_name_prefix_of_reference_interfaces(const std::string & prefix) { - name_prefix_of_reference_interfaces_ = prefix; + name_prefix_of_interfaces_ = prefix; } void set_new_reference_interface_value(const double ref_itf_value) @@ -121,7 +138,7 @@ class TestableChainableControllerInterface reference_interface_value_ = ref_itf_value; } - std::string name_prefix_of_reference_interfaces_; + std::string name_prefix_of_interfaces_; double reference_interface_value_ = INTERFACE_VALUE_INITIAL_REF; }; diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 2248f5f668..02ac8eae19 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.12.0 (2024-07-01) +------------------- +* [rqt_controller_manager] Add hardware components (`#1455 `_) +* [RM] Rename `load_urdf` method to `load_and_initialize_components` and add error handling there to avoid stack crashing when error happens. (`#1354 `_) +* Fix update `period` for the first update after activation (`#1551 `_) +* Bump version of pre-commit hooks (`#1556 `_) +* Contributors: Christoph Fröhlich, Dr. Denis, github-actions[bot] + 4.11.0 (2024-05-14) ------------------- * Add find_package for ament_cmake_gen_version_h (`#1534 `_) diff --git a/controller_manager/doc/controller_chaining.rst b/controller_manager/doc/controller_chaining.rst index c83ed97ac0..1103a7ae5a 100644 --- a/controller_manager/doc/controller_chaining.rst +++ b/controller_manager/doc/controller_chaining.rst @@ -27,7 +27,7 @@ To describe the intent of this document, lets focus on the simple yet sufficient :alt: Example2 -In this example, we want to chain 'position_tracking' controller with 'diff_drive_controller' and two PID controllers. +In this example, we want to chain 'position_tracking' controller with 'diff_drive_controller' and two PID controllers as well as the 'robot_localization' controller. Let's now imagine a use-case where we don't only want to run all those controllers as a group, but also flexibly add preceding steps. This means the following: @@ -37,9 +37,19 @@ This means the following: 2. Then "diff_drive_controller" is activated and attaches itself to the virtual input interfaces of PID controllers. PID controllers also get informed that they are working in chained mode and therefore disable their external interface through subscriber. Now we check if kinematics of differential robot is running properly. - 3. After that, "position_tracking" can be activated and attached to "diff_drive_controller" that disables its external interfaces. - 4. If any of the controllers is deactivated, also all preceding controllers are deactivated. + 3. Once the 'diff_drive_controller' is activated, it exposes the 'odom' state interfaces that is used by 'odom_publisher' as well as 'sensor_fusion' controllers. + The 'odom_publisher' controller is activated and attaches itself to the exported 'odom' state interfaces of 'diff_drive_controller'. + The 'sensor_fusion' controller is activated and attaches itself to the exported 'odom' state interfaces of 'diff_drive_controller' along with the 'imu' state interfaces. + 4. Once the 'sensor_fusion' controller is activated, it exposes the 'odom' state interfaces that is used by 'robot_localization' controller. + The 'robot_localization' controller is activated and attaches itself to the 'odom' state interfaces of 'sensor_fusion' controller. + Once activated, the 'robot_localization' controller exposes the 'actual_pose' state interfaces that is used by 'position_tracking' controller. + 5. After that, "position_tracking" can be activated and attached to "diff_drive_controller" that disables its external interfaces and to the 'robot_localization' controller which provides the 'actual_pose' state interface. + 6. If any of the controllers is deactivated, also all preceding controllers needs to be deactivated. +.. note:: + + Only the controllers that exposes the reference interfaces are switched to chained mode, when their reference interfaces are used by other controllers. When their reference interfaces are not used by the other controllers, they are switched back to get references from the subscriber. + However, the controllers that exposes the state interfaces are not triggered to chained mode, when their state interfaces are used by other controllers. Implementation -------------- @@ -47,19 +57,34 @@ Implementation A Controller Base-Class: ChainableController ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -A ``ChainableController`` extends ``ControllerInterface`` class with ``virtual InterfaceConfiguration input_interface_configuration() const = 0`` method. -This method should implement for each controller that **can be preceded** by another controller exporting all the input interfaces. -For simplicity reasons, it is assumed for now that controller's all input interfaces are used. -Therefore, do not try to implement any exclusive combinations of input interfaces, but rather write multiple controllers if you need exclusivity. +A ``ChainableController`` extends ``ControllerInterface`` class with ``virtual std::vector export_reference_interfaces() = 0`` method as well as ``virtual std::vector export_state_interfaces() = 0`` method. +This method should be implemented for each controller that **can be preceded** by another controller exporting all the reference/state interfaces. +For simplicity reasons, it is assumed for now that controller's all reference interfaces are used by other controller. However, the state interfaces exported by the controller, can be used by multiple controllers at the same time and with the combination they want. +Therefore, do not try to implement any exclusive combinations of reference interfaces, but rather write multiple controllers if you need exclusivity. -The ``ChainableController`` base class implements ``void set_chained_mode(bool activate)`` that sets an internal flag that a controller is used by another controller (in chained mode) and calls ``virtual void on_set_chained_mode(bool activate) = 0`` that implements controller's specific actions when chained modes is activated or deactivated, e.g., deactivating subscribers. +The ``ChainableController`` base class implements ``void set_chained_mode(bool activate)`` that sets an internal flag that a controller is used by another controller (in chained mode) and calls ``virtual void on_set_chained_mode(bool activate) = 0`` that implements controller's specific actions when chained mode is activated or deactivated, e.g., deactivating subscribers. As an example, PID controllers export one virtual interface ``pid_reference`` and stop their subscriber ``/pid_reference`` when used in chained mode. 'diff_drive_controller' controller exports list of virtual interfaces ``/v_x``, ``/v_y``, and ``/w_z``, and stops subscribers from topics ``/cmd_vel`` and ``/cmd_vel_unstamped``. Its publishers can continue running. +Nomenclature +^^^^^^^^^^^^^^ + +There are two types of interfaces within the context of ``ros2_control``: ``CommandInterface`` and ``StateInterface``. + +- The ``CommandInterface`` is a Read-Write type of interface that can be used to get and set values. Its typical use-case is to set command values to the hardware. +- The ``StateInterface`` is a Read-Only type of interface that can be used to get values. Its typical use-case is to get actual state values from the hardware. + +These interfaces are utilized in different places within the controller in order to have a functional controller or controller chain that commands the hardware. + +- The ``virtual InterfaceConfiguration command_interface_configuration() const`` method defined in the ``ControllerInterface`` class is used to define the command interfaces used by the controller. These interfaces are used to command the hardware or the exposed reference interfaces from another controller. The ``controller_manager`` uses this configuration to claim the command interfaces from the ``ResourceManager``. +- The ``virtual InterfaceConfiguration state_interface_configuration() const`` method defined in the ``ControllerInterface`` class is used to define the state interfaces used by the controller. These interfaces are used to get the actual state values from the hardware or the exposed state interfaces from another controller. The ``controller_manager`` uses this configuration to claim the state interfaces from the ``ResourceManager``. +- The ``std::vector export_reference_interfaces()`` method defined in the ``ChainableController`` class is used to define the reference interfaces exposed by the controller. These interfaces are used to command the controller from other controllers. +- The ``std::vector export_state_interfaces()`` method defined in the ``ChainableController`` class is used to define the state interfaces exposed by the controller. These interfaces are used to get the actual state values from the controller by other controllers. + Inner Resource Management ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -After configuring a chainable controller, controller manager calls ``input_interface_configuration`` method and takes ownership over controller's input interfaces. +After configuring a chainable controller, controller manager calls ``export_reference_interfaces`` and ``export_state_interfaces`` method and takes ownership over controller's exported reference/state interfaces. This is the same process as done by ``ResourceManager`` and hardware interfaces. Controller manager maintains "claimed" status of interface in a vector (the same as done in ``ResourceManager``). @@ -71,6 +96,8 @@ Chained controllers must be activated and deactivated together or in the proper This means you must first activate all following controllers to have the preceding one activated. For the deactivation there is the inverse rule - all preceding controllers have to be deactivated before the following controller is deactivated. One can also think of it as an actual chain, you can not add a chain link or break the chain in the middle. +The chained controllers can also be activated when parsed as in a single list through the fields ``activate_controllers`` or ``deactivate_controllers`` in the ``switch_controllers`` service provided by the controller_manager. +The controller_manager ``spawner`` can also be used to activate all the controllers of the chain in a single call, by parsing the argument ``--activate-as-group``. Debugging outputs @@ -84,4 +111,4 @@ Debugging outputs Closing remarks ---------------------------- -- Maybe addition of the new controller's type ``ChainableController`` is not necessary. It would also be feasible to add implementation of ``input_interface_configuration()`` method into ``ControllerInterface`` class with default result ``interface_configuration_type::NONE``. +- Maybe addition of the new controller's type ``ChainableController`` is not necessary. It would also be feasible to add implementation of ``export_reference_interfaces()`` and ``export_state_interfaces()`` method into ``ControllerInterface`` class with default result ``interface_configuration_type::NONE``. diff --git a/controller_manager/doc/images/chaining_example2.png b/controller_manager/doc/images/chaining_example2.png index 1ba49a116edcba1f365d76d4b52b3464f316a118..c21ab88d727c106f679e3e19c21739d0cd955795 100644 GIT binary patch literal 89572 zcmeEv2|Sc*`+rGM9ifs^wkWCW`z~Zj2$h{=YqB=RZY-&sHbh9a%19+-&o-3G7BXaK z6k!ae?2P4qkC{QsdFyxH_ncGj|9wB_)7w1D{oK!eUDx;eUd#P-`Ix2(%?73ot5&U| zQBzgYS+!~nX4NW+c$xA z9zj8KCnsJ@h`9~a+}@ej!3qWrf%Eo`mJn-*l_l{SL4H9Y9)3|Cev#t>B71}m2@8Th z_(gdI1;h=B*PGi|Igkd_aP)-O*_rPVR2Jdo2Se@C7ZBJZqyYYQ; z-cfy3hcmi%i)*uTH1e4C?kZ4or!yLkmR5FP2upY36a<7s!H9%GEj@@w#3V$B2W+6^ z=a3#tIG_vhBuz+wv=%ll5KAj((rCmxVUCV=Fo@IV2Q3^O9IPxz0waxR4uv|peSVp> zqaEq(NY^-l7yoQ@!U0_ibGxsP>Om}FXNcE|i;$*AxLVZ;VsnQ4WFT4MEbYz77n2S+ zpE0*|bR*uscDzM_>KVX?{UNO}&?rT_cAORE80()xdA zI0t2&6!#Nu-c_}pB8=|Vm9!L@T?In)OD&qc5LuT;v)@-qdza`Nh znZoi!jyXbruV1oxq0d!Jh^$WJ2RS>sKrO6DH~pA36QA{mPZTD3u_7F=;g6~j(S~){J%}+1-5rR%T5k$HOy&?*GM3lgh zueJP}6DC{bmo7w*pF}Z84*|n1s>#1zre%pQNnlCMc=&mR!~{ssBMDxJILp6B&&7!k zBR!hr9>^N!Xl?CG=FZ>uR^<2mXO&Hqq-|d)mM)23I6`4(9BmvO%Xbt4^B_#8u* zuQ}@I=mb=cKs3%;!C)RFZffoVa|DN0&=4zk2y78`i9ic}8IbNHoLR2ixO}BE~JZ)wBp~#^dDAYg7SQyvo5OE ze-N2S3$g;4K!9j%W(fuU#SGXw4C-iS2S8_$NvzPQ&-LXepr}j!iDbyXFeM_zuq$Np z)$;!zDG|vw306$7#zh-jveRWF`?hToZd$U;KTo5+Ynvn+{;qA3RQBID&7X>H36tX| zlKu*denHj$$G3o6_&VPICd`x2dxZsA*jt*p60$M`rn&;h{szir4Nz3k(asStH{h3q z6cs_JOz?1o<0N+~0D|)$rDkMw_|dFgNf4KBg<3j+w3Q&gos~5q@Nzq2^$iXE={&8-7m=YL`S%Ju6(C5Jpeifl*Dn$6 zCrAd7X8Dywpo_`OUsfbSuK~XzUvsw%?0S&iUia$lqxe&_gAlekNuvm;l1(y%4h>Xbx2~jE!s49T+ z0-zSyzC^9T{je}6LKUV^B< z$H54Qd|nM9cclCiQ8#HOzjDwmOiGxnh#x)=ssEi~2T-czgsR|TiJ6c@U8*pDGo!i~ zQ2ZSkRbdh?d^e>^j@JKuC-cKfN_gboU+y5U$O^VW%DV6`mOP+e!PMuv@)Hy~#L4Lv z68{wVb$dU^S&F~jG{t^8)BMqRU+_N`@c-#tD;k{x`PLJ5=L z>%U$Z$gMFeaN5z*(ca9-<+L5d`OL4-D?(~o6XYjRC}9y2QU3MHCFBO{71H=3^j|hw za>)MukpA2G0)Bo`Q9_pjc^q;AQ!Xn!90MMyaJU1Jyh|Amy1S7e2H zIa@h6J3`H@T^4uVEash-RZQ@w3zvj}b6A|@uW#$3Mynll0uRmMpnn4ypjK?xuvc7;o~m0+RDN@ zA{r|0;)iU=dH^J;^s>^e@2pn|m3*-#+uB)NN5O zegtg^y{0R+tNgIm{^g17Z|VxU2Vx~P_8B~@5&6Lnw|RW7 zNZ(wwKdTIcloOZ@KQC$7$xe_s!yi_aA5p_U>|Y}FO^_bVL#8&r2;hC&L6MAjMYI8R zJnaZGvvUNy-N4Sa#Wtc}F60m)2k9$FIgF|=_}Hdz3lQFL-0jchSL zK|Au-C6KR{`*R2XoqD9DIY`J6KJ`HG#9zzkUyA%olKAHZ#PdaXLhesoAs}&5^zfO0 z1W3#A^9YDsC;wOW06s?nKFdMajr$$pm^(WWztv$4aVH2#!5M6}v$gsb!3W=YvHRBX ze@vubNK~BUj8;fg_!|->ANz>}N(vMHCV?*R{rOy=OUHi}feMKJvJ(9|eE$kV|AQvF zB)Kn4bm{odB2mF#*G9i)g@2_)m$E8fNObA=&mvKwU)DxNzV7)ZZh<3)nx~=U%F=&e zN8DFVReAA$|0EwG(Hat6B`?NG-$}x-m260m#A<&Y-$^c-uJE1z|4I>j-@s&*fOU#X2t{~@QzGHsmtk*wce%~w<2$7I{ zMH>41?IoWJ@0Tczej}m&-AX8V!@zf&*vPi~Mg8?pW9hSq)(S$Uu+2{A>l8LMx?yc&yPlbvApjRv6ZNa~vpDt%z|J;Xq zg-9~|TViE?a=qg(rlVx?OA;H|Z~x>t_05zoiBkVUFtxOw!eBXu{&!*On@dBI?srj& z+;slm1XJH!5Yisf6&XZ`y~`p%EvEH;9<2I0bMnpiA@_Cv^$d%jmtTUEttVs0-x@fR zRGIW_60`idU~BQ;8~THP?T-8}7cKw0f-3{C#k1sp$&h%0bOWdqf)-@LKc2V7jC*L+ zDz;T>N{5cSn+|qR-P(Ghb>dSXdm#J9{nY!YRq31AJblc#qW9G>SGy}6^G9Eh`)A=8*Lrk)O{gt_(;ciTG0f>U2MZc zw608pN#F4ktLfFm7Hkf!T1`nOzw(dxwHwZ;ie0VkI5kSm=C_Js#UB@p?#TO7D5%m- z3Y2tme148n$uEQ@MBxq17sF9fV|J}sF~;JM|GRkQvi@&1{;}2YrF0!`=eDYf2$!3m zQmnkm9cIC`jn{Zzg7WpyLjmhPBqyi@vxMi^w^btHcuR18+Axxq!%uz+sP(&K39oBQ z_7S4S)*2#f@#;4Wy4V+ae&ViTpk>{?!_c|$rm8}ZQ708(Vb)PT)d z)hyQ`cC5cn@sVB{ubJ;$b_}$Vdt|CRxC)aL&ubIw5@FYpakw?tkq=im8uZ&v(W94s z+p*hIp(EWw#bcy`YY3NCIC5mVOm5zMA=RwdXQV$NxN>G3o9KdV9BHwMuXuA;aR_bS zmZLH7HkpeD~7ygr0YZQMxw!mP?( zjoX}P_++dli&~Rh!B9?{Wos71^@?}2sJ)##uA?BA24ma!_y(=q>@iK*Y0D@Xubg&I zY|2QzmRtpxWuikz{={Tboadu<=USQ2xHw*>9F=R^*&U1La=hoK`|dGrtdYgrNu5nI zmo2b&8EO?tnA?BiQF&sd>3%Tr$Y@7o)OjE#ij8!rEl=HH%u680=HvgEeeRl2&68(O zk3ZCLeKeEZWO`t$`I^2> zUg!fS9&xtiI_4$}7B9>fm=vE#J}KIRox|pPk5-H6Bq-D1qXu&l8L5S1il^RRg}yzZ zrTbYbohIn)rnbd#&$ZT0B3$cnSkW&%jO0Jxyl5*(Qb=mX~8I<3td)cTBU- zh9mCZw}zRl8NIN6i=8U2JulN3KK|BsJw_#H*9|IG?_;m7?cgY5^(`!-JC+Bv+KF

IbuZBaNY#W4HOD)VQWADst%M*)&%xc*giW4qBQ$UD4AZN4kKP?p7m*4V zH;gnIIaWlP`9KtBB>G}3aB58uZ2p;3OI8d>i`r6<)%p80EHlHLFMR^6(XY zR5;Cep_79S3MNrbyULZ7EE?(pc^?JOcv-k*@9QX6PGi=6Vm`C(Qq{(aURSsA^t=mX ztr0=cvdS923SzcZX&(=_^W-bggg42j(uURJ>*VIfbn$m2in!*I(~zMI2TocR@W91m zFS*&Pvq~rFe#ovC>vZQB++(#suX+YNTOl&IX4!?kI6!BwicYr(6t-_|&{Sy(d=61< z3M?8z7o%l`HE}e2ItbNNc9UF&DA_cQt{M5KUbv#B)MWoTBz`!Pan%^7i7%_i6JyOb zl-GMRj}HuWkg@99B4I$NCYsWpUbw62gZK0X=8ylq_CEb*{+5!i{GhyQpZgaF<=NPP zt@&*|@9>2aW&;;*|C1N1ZtyR_A&o9=Vm>?hp-zQ0T!qEs#r(YQe4p>2?`U71RE+QZ zw4hbxO@#Qi=Jk}D4g5ml%HJm7mi_k*3Z_>a&vr%3ZtRNm6>5|(p;@hvzw=Sn;2UcTfIxI5sM@Wti3<5$&ZcW0LI z$;ve!FG`CvoGW+>>!tcf@v*{LbFkwzGVd_xp<#A^jz=W~2 zjbOq%z>I`~vd%Bfs4J5&;RCCDK24{KQfRKHL&b(7m{*XX&H8>()a#9<^W%;az;i#B z)XLYf1IL=%^*63gT1$=5yozF3a)o|;6i1taf|-k_X7zWjP67@`Qw_Cg`E(k^HA;MC z?JF=Tb}%W$5aH!nfc}b6R)8LGdhQ0Se{Y*+FPm2W~)D5tqsnmcLJ+8e3Nr% zg_4DoP`p-B?RsA~j@ZnG;5s4EvSayX%F{r2WxcNqsl|D~G8x{SSY9S?`cwI?-h)#w z`^s9W#rJ^IM?zg!oMt%1*{tUy3MRD)EEDs2#ENl!!Ryb@WV%q&IVpn~UE@eup3&67 z64=nx20t@zpU2nzbSW;tk~kq$WZaNnJ*lme2%gb*@31r7A^+(EPws!maiSYRAU{Z=;Qh{uc<#9{Q z!0Q*!+W}t~Ll0)ut$JX2MzS0EO{9<%U4LL5@@)QVZ(R;4d6|G!19H`R1kDgyzM1;P zUU}8v>g(BbPKIEavi1$JFU1B^y9u&u{`3dRHnqP*^-0>S-LBP?y9mofskUO=`3-ca zxp5mTHCxv;pwBy03|H8zK?x4i>fBcoKHO1IRV%j;ll%hszWr&%^Z9e__cfv|8y;v2 zo_WI-Kdv-8G0N<>iH(j9z`p#3Lt@J+x!DMiHq#tC1A{zh;!Qp?Q|s5a*yr$*k=(lX zr;wwsl|B|x!d9&YqVAJl0l6is{a>@smH4kgCF}7`_k?Nn0Jav{S>#pa(qzIFE9nwS zD?24W(D0BW-e=~aF|=Y&hE>%z2pU;bI9emMX>9kzULfJN^t}|C;1y#V5IoBgMpMql zrN&AiCb3Og+jtB)0RfE|$2L`Y^u=;nlm&%bSKn4Ud-hRmuPKP~NX?BUC1LaPTSF10I5U)s z=EYA8g+-crs)^b)v-QP!r54E*0eTKd4}50qMwF0^3_=yUB0V@7V^-#mCgZYLo4fxvJ#9YX!K z4ARBG3Vr8VB!O1}i{o{E-9~`RwIzSb)y;0zf9iA>HqfBfTN{s46%&*b=)AGc z8FC?HIER0TgDw_mgCv*ivSX!l@@G5Rq}da~LRsv`dKyN%S_{lJjz5!rNqVbu*S52) zAAXx0xs}K8c%1i$T9k-wM2t(LfgpSa2C2JuQF^4DBLh;u7tcFpo0_NGnr+KP(9bQJ z;)m94+O?0-*vY?R&b;(eMF_j%pj3sF>)@F-6gthM;G_d`+M2-fh0ivq#<{;=--e9j zz&JDoP5?eC3G5Q4>AhhI0@=DK90JFHQMX?@OVe8#NE;c*;;A|_iQ}8>aEmvF)g6Xb z@#Lz`&5S34AWifd`dk_Fy@Yx~>||ntLa0I8>~kx!AoYl&QG%%Z8aoM=H#Xd1bX&~P z!8gtR`c5&;;lfc(gD0o_XD8YmQAJ*E(;(Jald3gIC;v6+=t}l$tIu}Bb=s@E%5~`2 zFV+DIo0}W?Q1zjdR_-SF|Eent2P{W>tHGnUv>@RHH}{`7(pw$PWs(m|pL_tOHLjEE zV1j8%i+4fYn0OXIRdq|iVo*|Yvst10IlP<8KtsB(8{p?2+fW@7qvKttx~VxsfB^lk z9M)SVi?a-G=y4z>Ix;_==G#IKjSZCr1Uc{1tDQqpRBvOa##hosUi&Fd#(_ zgG%B1Paqu8NN9^yq#B^4!7UQ8d(DbGU1}Bb+l1(6Q+64tu$=>%a9Q_&=aps8m|5bt zdW|Knvq;co;5ab5px92IPcIqO?zDRVH=k<+ZT|!ns~iN ztv@27|CFnxsK3UuyT zu5CfO6=Xf`(D5{BR&Nz?i0qSefR{MR5ja>`btMFRt*%fL|e;||fSIT);kTs5v zwR-d1TNpKNGUHvv8~vesDl4pLc*ET0$Ac{FmFwx)WtjHJ2KeCtUQb?cp;$(6DhgB0 zCewv7&xbO1a(2l=^*6D~3{G`2XmTGsypb_He2re^xrb#Eoj$HKo|wLhP3iQMn~wvh zbmwA1+cHHe+u$y;dA9oz>xY=6+8d>in!wS=B0M*BRFS?Py{3)Ei?tmn>8LM*iF01G z7F$v#OGcnf*!tGCO^ye=XotqHWm?_{9eHVD)*M)s&gLgS0tjMQ@vA|0@_gwwtjh$qz*>u#AV1~xy){f*EuBJRq_tdW6O3?h> zh3$C1D$O=!!%^NKYqftD(B$FYuX*%*vj_{ z2D@&}zX6`i=_DYakGWD-5Kzu8WmQ)Es6OVCEA2GA7AHIO)=bQZJ3F+{b1oS*F_z2Tw1yeX2ZE~1Cs!mX0+2Iot(a1YBYX$QrEmiOzF2yG>BLpZF zcFU{Ms@-kTAbC-0WXW@yjaCh>wFMuP-Z7SvnklP;3eP=&K^pf=NriXG9DI`?&o;@H zD1QY}6w`YK-G1wG*BL6vZ~h@5P*c=7okp(4KyJ z4@5P`GxS5s;dhLq#UaTm#zR=!Cg}SE+K3C@-qa$~#1jHX1Wt5O_ptnga2 zl&0r(%pO~+lyHz{O3qD*$fs=zkDr<2OgbrhV%TGWMNLa9GO_@9FiHi*#dDi8x5zpA zC{{?Law{K){iWO+6W3eSag9ZAv{sr_*O;o)=%H$>-pVLboN_~(t#;qr%6MkP2p7fF`VXOFM8W`GUF_EzZy@(?exU`R>|cT z3b-!RbYd{AiCz&A9aL^qjp+cjGe)OlgT`wia%Gariqsd5f&@v%`OE?mG=&t&C!b8Q z1ffdY$9~=RJ-=~DkWH`cx<2V_PoCwK9 z`l=&i7Cx9McqZvdsud^?A)M=La&VptGxtrR5r@Lp#SN+pIwD|KQ5nhesU^ejxf!%> zFs#uNZfzP zjW~Tixa=T@5Nix~Y0__z>2kr@9Pja)hB7B_V;d%e9p=h4-O$cX!P4hGY;i@*efkt! zH5J#LsQ>Qty}Ks36FyI?OK(bQ`ripgUByB@|;46&Hm96_X52bQd z_r=7enj|>V7!<)>PQhc4Tpf_&lIL{-loY%GQ{4Ug$+;kRjxHuc?R~kQ_=^qZ8k-_+PXiHv_F9*iQ zen7l{YnuZ(SLM?8}EJoD%NCB9}SH6v4!x3 zukOD93-a$@tK*4K&7U@V6LEg+hRPd}!Q!nvyvHRf)hwuAfUIV4R1gCRd)T5VsrOYJ z*XW!0F#D{pt*K|NJp^uO8wIQ7R4GVA`>)-&jX>y`?IT~&$+P(a&6xH01R=efst#ZU z?-?7fV_M^D=8iisxrEtuWQy?1GpL`qDOOO-9Vu4WUMJfDtJfHrn?$RFj61?>au}6j zB&MdJ;R4$!d}$Sh2XL07qVKnmRG*Gwamnc87Adb{uUrtwTqtY-2LdC4s`irWBrUoVgPwEmK@V* z0gC7*6;>K?WE(ekn3qu@4eskNhIGZcSmb+MKy+6ze@KXz8!_o0C^q4-aM;m(L=HOI z2FgIM`tyDCVEYS$o<#B(HHIU5a*M5`2h>$*I|WpONd{9w<^Lp>az;MpV|06tO>~UY!g{Fq(33vA&c4JDJGg7|O>Way z+4f~4%u|DzwRZaP(jL%P{WCjkV%{0DI-eDfKzenmiEhta95{ITnE7F{*!L0!-m5#b z8~?r+Hd!v(`#6qc#xMtfo0qbFzCI+%6(raU=x%%YSmd``m1>nb`QBHd4v8YJ6Pv}ncgs06W`dxVw9N#N+0 zo0!wSecbl_OioOzAJSH41U3aSFD>*Fpt{idus74bEV;EHe~WNj!s4v^s+QQz_Qg3{ z)D=B`*J~1;cyhrI`tjo-3Gaq!4DO=t2K7(7Us}B^VYr7otkv-0Dj)I*$KZ@@PX`uc zBwW1R3Lh7B$0m&{>#LA^0iH>(eSQ+aY+N8ED=7!%&rf|}h?9SZEmJLQNM9zuu<@{L z{AAvsWLNu|j>>I(2kdudhii*nyOM1rkkWS_4QiKy%1t1EjXk&E38Ej10o%s#sd>rg z+nbda$38`SSQ1#s;^LTY0As&VZ?i-!1T9DCqHI#$_qAQ=gb` ziJ!a2Y`y>zZT9+23-R!Ymg&yJax-x_%?yRt6z0i%>@vNI7gwOobJxwcj%HsSyc%7f zJ&F}M_f9Da>7DPL*|XE2$Ub|py;yhu%|~oAOk&IeY1(%$Wj(4tQX?~NocFZz<+Ocg zcr6~2q;;X`N$LVR-^KRT9QMSc&5p}o zvvqAE&)MxakGyCK23aes_F|t_NKy;FslavUwrxU#tnBEWH0GR{&8Pq$C6pW)xs?d_ z#@+EOq(9p)@RTYVKZ8vhn!|$BN{xGSdtP50K9Wb*i}uR9?!5$Y%v0XJb5ah4&Co?dc>mz^PO>4m zFB$@p4fe*_Uuk;NW8*wQjwkV;0=virJBpXJ>*8xkhH-sGSp z?uz_wAFBJBvA54HNV0c?m+q#!zW06l4%%JpGAuHUWao~cr*2a_h1$wnA4KVq@4DNa zD}xn{RuX@H8fQV6Rq&j?IhjSP?p`z^ZH%DnMW($LClcDY&a%ep-t*aSH@*kKHE`od zF$p9~v2Sv2~EDnN%3%%T((z!{COr0vedeF!bmx^(3cE|;OQ4)AAG?ZL_Ko|O4WrMyaVJ3)AB zoZi%da_*wwKbjHNVg71;z@7D+BW`Rr@GM!~Y`@Q~Cuqna=?$1IB;a-DB>-=&zfAL~ z-C9i(eq6O0oP-sSu8MxcO1-F0@TVvbvOXPI)Tg|)51G$yN1SzUV?2vX$!#*)NVw3H z)!dGjL>?))!LTLr+t_O~r%g)pocoSU4tIR$i}$T@(PDv*X?uVMgrPoB`&Ld;Ps7W+ z$#cCT?c6)! zR#Jt;HK&(0!rF4|bsin(hScA`PE%qA9}hp%QFW7>1CZiSLZy^R)NWsQS#V^wZPO8O zsa5k6b3#fSj}}9FXA(F9lgL?4E$L4e2wBpc`I#to#Y?{r>y`yEf2iP!&nm8kaKb^> z4cdKOtTk$fO`OO5qABMZiN59qG-zx<-8;N7ir@VFwe1254n^Z9r-uu0Jx{xX!aPQM zE5QABxgMCr$jTFXCVN078J<&?;&b0P4?5Cnn^r-{m3uzcOEqrE?0#D{?WVW#K(~lx`_pr-Of%=#Zd6J_pk3SS1?^jfcTS8``1xq^jr43qfxNEw&Kf|5 z&Q145JNArJ@kN4Wnbwfh)pIvgSklc+@b}nFk_v3mhM@Bzx4>)CLE_zoEtca0Zw1{y zcI^r_qQQX2hP^8dY_n*tdWoI!%yVq9zZx>^wzgT8WNefQgm?FscYC_UN2{r37b^Kg z@?KogWE_n}K3IX$bXtYY3J7_(Iza5#^R za%(PG(mZE+4K(eHn}*7x0vKku#%g zx2d?^DdlR=P1}%0myC@V$@45b)Cjp_6O|+++NqRA6k+=@PR@58c+z=)S=x8^qa8xy zWV~9D{pX_E&Ly+Mr$;{M+*MesWt+TnG#?ps*TXZ1z_J_ei7{G`Zu{f z2USSW8YFA19?-7NSH!tf)Gh>Ac9W(_Bi=9b(wHoKrWqeGXF5A^)n;LCYJQ-o%ah%@ zCBrH-BEs56vmsee3%M}wRd7J!A`CPip;9ITY*ibzp)~a~{CR+hqdJXJX`}1kq|h=o z;44{urrzxWO*Y&^GcR0C9B0Nb(03OZD@SYP;%!u$EJguU$fV81e=Mc7k9U@GSdaO% z>+ZBsWJsJGpX_xKzf;?NN9#0lqSbb2OeZ#jNur|3OK6;3ea0^dkWq29iHMGm3ZN;i z$?K-b1&mB3ka`3jSBwtQ9|)B|V8fn^oQn0C!Hj_J5s$j+UAga6-ng6%oa-;>%)f&x z2tF#(guyaB;+VYCw-q&BgaN3MUd#O^Fb@NBrFlyz5W!1gF4@C3;|clotZ7Cw@4A}j z<(OyZW=h1EC7N=CXXDSk+5sA=u1hQCn@Xd!-QjKWJto6>%(;Mn1T_}6u_OBIUvQCP z4>q;6FvO9h#BB%lkBK_8pNV(!p89Bxr`rcl+`N&(eDg<+e#sBf<#4x3wy3s6pIqTB zoasnX!;oY@qyhw#I-ot}^iuf`({`h%xaRQag$O{I??s-XxGZfVMcr_DkTHjj@j~~@ zD%lGlo`UfO^X8B%YyMl_=&>=2JFz90fmS-1-r_Y)=8`u-RG`@-v2|X{ua#@Ej*dVY z!tn0aIP$D%S2Jrg1qxz>-HP1wRq9y1KOSn|d<>SW24IxGl_3}y)S=b z3Hw>-yXO}t)}wE@>6R5>qvE%-IvRPT#Fro1cLN`%XENp08CD~(6v$lAluydX;;#_; znedM|wo#r2<&3iZjA+jbV^g!|k*>`HRjQtEf>mdT9Tk3B6rQ0aq3skin!T2W?Qy9c zpgLY>v>Vp@^07f?&*RLRP)vQ2I-!{h;QS5X?OWXLnmJdCpi)hwcF1^U!BgUqVn%5H zl&UA@rIzI(?Dx=VLCjLEIb)NyO{w9asn5W=HqIXHGWTMOR`W#BE;YBd+G-0PJN6ol zDz+RVuXf*x;v#Y=3O2xu?yU;(YQ1RrIIRso21Iymp(}iKUEZ-@&VMzHC8QbZ-sqs$KLw;8eyO{N)@y)BH;K5 zRDqi#p`bojlq2HME}jPp`&Q4+uN`S~ELI~iu!*rL)vW7zCU~V$)tvcD1ld?hoo`_! zPH)#{z=v-r+O4lYD%jXG1aB?!%4OaGf{o-N83o^B?`h~Xu;WDU>5+`nFE_LldSnVi zP)a$DXkJkJ2n7s5Et1z{P-XxygQA8MBR$aZX%oDK8Nw><{^Z&Yp;xI19G_sv^ACQyZ&4>rq;H*JB0`$dHZUFS-A(%=kX#nt~#OyB~0f>U{=Z78|(}HN(;X zg|K1o*jTI|^!7}n+N*Af+jE<$Y!>5A{UEyuV!qqo8-$&Reeu%k7tRgrG+Iyf+jcgP z!3hT>t};f#d2nn3pp*UvhW(scpwmy_t~96%CLys!1F=$WIXlrg_R-8TeELuB%#8xS zV+}j9#y7<<+Y-dOaTmw#uxtSa=D$naN&eBvl>MICiVJ3-dBS4D_6B5`>&^6&C;gwi zjSQ)ABcl6i$_xg=S~PE317`A4BqrCs?PO}fu%rhlfF^=|;1NL6uB@v7a4*~xl3L$N zpfXY;rjPXn@Q*~{{V|`H31U@h z_E^Bf&c)Bl>71`yQzU**3+am=${kuuZ!-4Gd&UMt4o~3Mnb~EwXG0Sh33%3VJ>hpz zBAZvGSbU>H6(iXjEA-Kp?MdDYBJ1TI>n?x>S8mYklC9f1-gq9=|J(dhg|^3e4NDX> zHOQ{N8V`wFR39j7?I1Ie@d<1ssE_pnN)v${SnNyKBqfjA@s3Sb(C=Sf{ZK82&U$BT zrjeA(a7Mn#h-wTo1A#zLcNMAdlQ;J42=04uWm_oiMS_8b>}np|OB`}~Q44(Fo99Lw z#Oe<8doRpM?*;TJlK%BLd~D{4G)-Ul0lk{$I)D%@PN``bc#z!+TKzE-SEF}+TjqvE zSAit&eF#YbF5${^*X_s5`VJtw!?Y}~M)?%=wK*o9njQ(YHcgLc(s`n=R!xXj@xa@R z#Nz{R)hna)(xmziYFT5JN+SY$Fo8ZsgajwK8X8Hnp6^?15Isnp+*jMywKU zf&e8xMC=>lw1CewCxtJ}CJo*e*GA2Izkj-AobQb3r;{@oRXtlrThlEKT%)csdeY_v z-DZ`9?Xzeo1Ub5(!F#OPZisH-&EdrC-@ubDMWS=QpatCFVe@1sfR0sg$t<6ugO5#& zf^KtNk1o3|N_aJvKa~F+X>P>|*=00ycOZJ1wAX|QrUCbydGghgt74QD7EO*#y zh#4nM(+k36;Dkq|Ij2ZG=-t*uBYzZgZG8M}{zNCM@6A1ZF`y~s!suhF({~kgCh@q$ z9`tC5DeYp2kG0OP9UaB-9}%7;DmY z`Pywl_O_bWCW~1MErVg(d0Cx}ke4WPdHO_^pqk12C$Q;GKO;>0>fA8X5V4 zi#fB7(txWP#A0cPD#50YAX>%ingG7&)@M79fRxJx1P+a(^gU|d|GQ_HjMr&HvD@MI z#-nAtTwm3<809+HmwHICnlUHgBY=_!i){Q?$o>h88;#FukhX_UURaN8D!R75G+TDA zVbsU2BVUB$7NZDlRz3c;NKDf0rdMmt&t*;=YA${<$xc{=z`5UT7Kpe}erQoMr07D^ zkq$%k!w+?>@;U>D-|utHDl4+4X5kD=1mpT%8Ybc2 zlQqOnHnwJR=E{3|dO~rh?iX<&0`E5r?ju?K7N-Lrd(s%aTY3B~A3J7&;~4HPtZt2qA8T*ebIxjK(iCPZaax?gUxo%?uLzId z2o2OfxlkpkXX=s2{LBvYS#b<~X#5>LUR}G1S8!bRWkZ2}gr|*t>2=I-W`Jj!^N}mF zAU7#@&BLdWrdV3666}TP;sfQ-O&f@;h_3u(365?Otf(r8o)b@t;w}bpA>=08oe8Z( zJ0xKbI&jZ>=jsD#S%Wb903Ur3feXJ!gVAKol&XFi&CsiGEk4bpYJIX_)FspU!i2)t zdm?+svKyJqhY-Smm$K(1WLsR4PK(~?=X#Ro%Y#?v~PS6Au zVw+afcnLaJ0Qx`GUR~eGHIsD~KIwd8_hCCRH_&}Z*tB5>HslXkQvt|UV8 z2~d=hpa$&kg*kOk%oTUY`4m1jDQKMVAf=t!${x4znIQ}9&E$kE%jxhAHXZR?@!qI; zSp#L%WNoZ1u3PpA?BPwj*5i+gN3Lv@z;H%+wV%^Lsx!7Y48)x_?Kn|wyszc#a7w2w z%kh%~?am)=)+HQ%P5sG17bkMRQ{`w;)sFa%R~h#ox|wodre&fJ0MoG+mVv?sGx zHq0Q?+Umj>=x8nHPKw!`cAGybetNQafhSmI;ucN2goc|OwCDGRM<=S*eax&*e#8PI zBG8a^+1?9m#38gCdVoxxeWWv!n%wAXA$xaZ|GldS&+&l_+a}&Rx5KqD61oHmZ;*B7 zM!)I|*l;x%kHPw%jZX5zzFfnMsfFOfUSl&I3Wh{?z84w9u3Z(|*;(L*Lr`NdftxPN z(##=j;=@tB5f@!1JGcT*rbQUu-zJKP_Qax7u=OgU(Pr5Bj{#egbyc>-p1aiGJ|x0j z_cZ;r*m$b>Knji$eP*DjuAu-4mW^GexIX*sLI@^}MGJn^H-ooW)REUq!#*JYrZD89duHg2il4@H(4d+XcsipN-6@9huGffw|9y{cl`NrQ1g;x)$@P8S@tZ|v|b zZV<{9>CYIL!6uGfWW0i;^1k}eEmjU2>o72P_2DFhsdw}#mrSvl6}$fAv7B(khEe4@t(M-QKE2)Sgf9H@Jh5$%yQb3}@olh9-rm0X1+S}t9nA0yYG zWavETL#zb3H$l(V=4%M#$LAYew;F+6S{IvE;a}}^wDeXENY@OjNX1T zF|~qSX&ny~@_i~ft}Rz<;1)f4{g%Du*Tp)|s1%DJ2yy9zp2_aX2iSeS znr(#5SF!u!&))Y^i2xhTnq9-#5!mAs%)PrWck;!$)Pyg6(pwrxGuGx<4%^SQ46 z;f{0OSKCcQUKZ|8xtzz=)A0VK8>mo%T^|*on6A}3kU>gZ^eD=!Y!RWuE{w|#63UV# z?|VVcRHXuJN%Ja*5+2PuOVc=m2A~;CgOP-$#@FFdE_HQI@LTQ1&S+;%aA}f@u&GM5 zOC9|TYc;&Kx_a!x8IW?_*F@EXk?FqSg&IHq+;R&q=v>v4Iw6A%=-$1MGFj7?1&1>g zYPNx@*wxO-)OwtYS>Yy(LxXG5`i`A5lacwpjbp#J6x;80(i5$(NLY_qTm5n)vs&7m zO;P>PB42^=RL236c4?`S>w8|dQ>B&pT5=m^Jur6ba6#3-zAbJUCqmbd_?rQHFtq^+3tmsc1v%@Z?rV2my9 zPkYj%TqN@@nbABCSVxml|6;sin8{KE5f9StP_SF_s-{L`Z9g2lX5DWg)1!TT+fgoN zV{uUX$={sQGCQ56!46JBS~`OUvSwn`P$Y?1KL!*xhHuti7O1c#No*ujxp~s)g*nfNqxEsk0W{p$*0ezZ+c=hB<^8^#u*k?2>aOvzYkWmYd%M-nz~ta%5t- z!*)$x-1dHKj?aV;Jow>MdNK z*ivi)a@phgLL8)?!ma-%D0XOy)Q=kg&NU4jT!o(Q1T`_qR7~C9pQmZH&=o){s9ZaG z8p`ppCtG8_QwmV+w4L~|K#%L_0g#R7Fv|7Ri;>PbUS7zgX{N2$J5sf#o=Xzwe+>YG z*i6J8A{bC`g|zj1n8v!S9LK0WoAH+38W!W6*9Gr;(i2Z7#qJ$vbfEZS?G0$l8jijuLK@<+d?A>N z+qEqdB@rz*f>ox<9TU6+%bmoO=hzG4E^OiK z@J36UZD0s})%(t6ZPm?B-t~5Lt0@aX!q*F1-AJ62lQEm1XDUvn`2CdwyKK=zCEfZe zkbQdzqGQBoxz+44IBQzv3Y#3h)ox+Hod|QE2RbYmJQ{} zcxtLnA{zXgsr_F^2|gY~9d`AZ&)enl(cfV$_-=q8_%=XAg0e(?#Xh5Vw|?JzC78V{ z1DK`NsoTVA5u2g^2m4l42_bmV`5o-F4xdhs#e}ffXK!9`uGn5adpotrruV1;yj}x( zW~lY)@Chve+KUHtvL6vhrXFarY0}0g3-iqR~_sf?BxbgxVTXc%rmkrEr)>k-jZT8U9j5}4Avn;e_jHiFGr1Glxu z@o`?7IZ<0YV|$0oHX};9%jUW8qG9Psus0U>;N>^=PRYxzMOAOP+tlt7IS6W>DB4{i zq1Dk<6&xy+5qe_&`tVY~jcigsHoEd)wvg)tb!~ z;p*4MA2^$f!DMci7<8YSM>+k=%cUb7^$26VCQGnA?Q{QtSeLUyK+cR z0qk6&b(wBi?9K6aUmJ95@>Y^Pn)k4lj7aVMiQ8`RY5i}W$sTmTy^hiW8C}q_R!i&j zd^ib-Z@Z5i-pSRvO?>a>l+$Bk2H?F}PM%CR2sL5@JB{+(`28n>a7Gji2VSMlOv9y~ zp1x=&sN0+zJ$cJfh@-o>cr28eflsF>f9pZry-hNbS!cr!7R*8=^4-#ejf*5-6-`=; zAXPfW@p%k##VQViVxT0b`F39 zN(@i5eJIBjSDkOoPIL<2KM^;&yVu;wgGaK%L@__LbkXHb&1F8zler6=E;R_nI!Xsd zX#)eBW$mua%=pDs?R}{7WZ)glaW)m#*kl^UZ1GC9;=V@WwH*v-k#qNE=LeEeT}@_t z5-rt|+#&(#Vmq?B*jH4kMMIX5(dyX`wuOCM^^SEDZ92Sp>-hNU*btV3Fj}wf$w~V% zJgy2D$Y6bomgj^4{!Z?RUfI!mAb-FmJE5PtnF{27pO-OnaX);>as_mHJ!dCuHXgY4 z|M+_Auqd~-ZCnu*R761O5Geuak{Cdcln@Z zzBNA2e%|N%e(&+y|Lo(~?(tsty03Muwa)82&+8wlCYrF8^`T=gw);7>Q)=l^Mx*^g zZ5h+C-Ax`*d6eq>FABkI(VOqMfV#WeafrR?vwy3N&5KDB{@`Ju+!N0?bky8;bJCgIa;DfuVYch7zk zH5o){Wi4%N&RgX%A7SF#Ah9&nkv}yz0#7-dVrF@L<*Px zU`WcO{hOMsMd5qpd^5%K$#B!hUVDJgd{(0KL%SnFIm6B%I!nrAx-;SxBjH3hP5{Aw~#C zikT}J6yug~$fin4(ZrOJ!UyEfgZON|N|>ckGeC~QzFwTquZ|P4WH*wivb`(MB*lwAgdey)&B=!{`WEr%cS5_WXhTlqO#ZU zML{2=46Nl#3IE35UbY!Obs;En@dTXcEog7Cwg%}7Ez|Us#u7y;#<$sDaJD5Z$G#qW zoy$&@=qT^B6GbYGFx1$3T{`7EuBV&%CiIFlBArp|Y0&^M*-gR53y$S%az3SBTnb*l?deJHQow z-sFTZP2bQhFnKe{Z<9jqf+$u737Oz^m<{@n<#yloxPoUdZ66!61uecTySi97dNds* zucSvc_;Hf<-+`%i3;}s3bxYUh%9GKv1^cJv(rf;GL}`rs;%DXhSGRIqLcyxNaZ~Sh zJ!*0bq43il6JHd_tPG<6{9dQ7!cER>6wV-k`+wdwu&qZm_HpfrmhSJ?IkbW31bLQn zmpU0hUFvA(g3zh!V*meVbrzymXN#0JSe>jHup!#xFSpokzIUo?M6r(ovbAPN;`xA7 z!^KbX*=ogmss&$fa601o+1; zIiENrGeCAQl3!<@10+PivLuEm4leuI{Pl}axVCc2QTz4jua6YvSPGRVrQvxQ;}+tU zJ8N?Gzml|lL1XmL5unk9D17{D)7J80VPs&8o$Tix)=O$2CKu!A=Kb@Vi0<7d?=aMz zLc0+f^1=Z0E{#m-u9DO#Bn$uOE>Nobd95GySZ@yma@sP$Poin0wjr6Q>x&ospOHFs&Rzee=k_UnjPT@@KJK#& zBIGfDmYX1|S>%0LFHCwozn3nk_TFia_1OE0f6Hm+Lf;z^&7XY@*qzFi7OMH`<(X)+ zf)e0VCa9z7kLv!$Y_c)<{cOwKnHu7-t(eTqvRs!?Dhau;LyQ&w@VUN%1J4YjD))^+ zYDQqb6afk5$(B0$NL`KE0)f`>cTM=&VXvH;`P4X0Xn|woW8iP%{|!{8N?$9Qe$-q# z3tCQfnJdqN36NG=O>**IB7tISTrXZl5uzGF31Ny9I{Z=()bq~6;0?d|-MTw<;|dIS zdLF3WwfX@`)eX1}{CFLVACr{C1Xw>YK37NSoPg^iDE89h#47*o_fMA}fg}O2bXLCy zQO4{{S5H6UFl@sj(?nvbSC>u;+Aa7}Xpn=CHmj@f22@2NCKUi9WfeG%#R8g;&RUXP zwcVoFCa^;*QZE-n?%lzqd;$KJ_+P)c$sS6ElhOf3*%KT=fRDx-Kiq`w(#2~(qw+#V zKW2I-jphpr#$2`BXX^yjjukTkQoz|}@wq;q-$^(BlO*EP=*Z{i0LlVr2fFF#Mu3#A zL2=zEm<~qxN~=<@&W*7)54`7*6FZX?xtF@Bb}iV>NbOrS5%pWrwUkn*dH0KN05pr} z-jc4<9fYEbT!1IXA7}Cpo!Mv)c!>OUKR`Qw0ZMReoCmi+9(s@XUFe~3 z9y==OL%6cO&X~3CMoH*-!!MgiI@>2Swvl-IDF#rZMLnW!aNe2X)!+Q00vrlffw{m> zhI#>u0tUE1yN04L7@drVLoowX0P+zKKpoJ+jT>&jm7xnTtgICu0#cXd^!c98H8Z$7 zhLEr!LV!;e9)*Vcc6mp(V!E)8IbWL3OYUsTKVu6;ey700VV7JLB_~Wn)u-L{nQuk(yL=p2VMRnScV=^$%eG$Gd;AW9vhZ z+N}z3l(1z9|6%6R`ey>}@zb9J>mPn~-AY!Q7LaX#f^@#vjH$C@zcBdnETFBg9a-a+( z4*4lk_X}Lf@Uk`va8WsabkupDBG0plB9V0mAS179ayC58Sp&?i5n9k)2IvTO1FMQSoMMGp^ZxJl10>)lPTmhqh?$o)Wq2uDa@DUW8+-9T)wa2zUSif4?oxpi`V zHGf@!DDV%&f_QU3Vo@(^zN+n)8@&JO70%}7TFU^&a8qoW*L&II`|OCYK5BwFi$sz~ zpzaCks`l@MS^A=2azOi(y~Jqw(fD?)jIF2 z*AML6A95dxjK!9f2uRnH_6)=;X8Y*5DcQdt7!#1 zx@8c#alb`maw#B}RO+d{z%J}u6?n&|VP2aErppoZI|d2pnFftK1Vpd7u#yAJ%_u$i(Tkjrf*^23`O!(NnVF~iypJ_|y-Eai*2~Mkn{gJ}IWP=PQc0V)pMaYI z05>OYFY&8|dleP|hdqtk_`szyI60zsBa>QQQJ1I2@~tJX<+=O_u^%B2$MF<^|1gki zO;uPOv&&_$GfP;=42`&VZ6o=_>DO%6>Pvzo?w4Dc!`(CnI#PMaIr+;ybwY^SSnQwP ztkBHB~Hbew9jz1+ymIwb8y3r)x-oZ@`Z=1&#F=l-Pd(*&ix$~Cceb5rnN&FL?8 zcxkdt`aTo=tKuAzxCbkdi8Y?RJbeQp;C9k5k*t4{tkn0IOUpPEThpmm0GdrD^t>ry znp9z!J-r9AIo(%`H!b%;XfyyuL4U)V>w9_J*<2s^7l;SC>j&WiEqa6G%mPWfCeq_x z!RzNah%LFVz=%|fsNuL!x@D% z$0)bdvrM8nB;mu$$@sHc9QSPmmWx7Yf80>$BY{-Ft0Zc2KiDPu zV6^Vc!ok2qpd`SNqJ1c8eI)bLVC$U=#m3k zGOxiWy!DZYYe$0!r;=3qxJ{Mq^@qXH`*#IK^%V1XCf1+8c_u9OM{g8`Mm*e-u8zn? zcIxctB=^h1~k}8T<>9#@o7?Inm*2pXs_Y7KZp#GRde)@BuBqhBD?vGV%cT3PU^trs z&vZLy>guLv2{o;SI3j@h4{XJEu&G=J^`-v*zxtOa_2v$a%9bm z=s4bq(%laY(>60JnkRvz9k;}@q8bK6??8R{y-JTgVrEb2>cEo0eMYqUD{?BQe`-j= z>}2CMSL#^WthBq$c~<&>RqXUZR!72>-0;Exz?raKqc5KG<^Q?Qf$yIyKx8hZ_=o%5 zCT_%DZ{Bx>(y_ZN5|km?4Ds$u1q>}{`Nel7DfQzytACU2}8&;2DpS;pXEx zHJqOU0>#5HrxA6j;tF63tC4XTdT|zrL$-Zci(-GC8l3U{l|SlyP1uy8Aq1S+t76ZL zwf+6()JhCA_PEBTHm$LskW|L+r&$PZOZIUOxRVIYX*QxW_e52S^mt-WKjthAxh)pd zFYp!@hsr%{qj9qnN-3HEZHi5s~St*ea%ED39|U6~zw08zHd7*>e{wpn2miR`mUycuE@9Rwhk_JLgA)e?5n6Xg4MH+@F6+eWCp@duns4)lO??AW z1l^D>*WCD}Owku2^jMyX`v+pquLnz+MSZe3wyRpIF+;!9P;YlOrXb#eE# zoeh;_uE>Ng zaN_-}`?zLaj$r(Jaam(2-_~XtVu3M*!3Ecw?QI*}L?9?V-#*;hXi9v7FE7nzi81AQ zBSZMv^46f4qG=_{=*9!F{3^a@nzDZS-7w&myZiLKGOLJ zXOv`M`|AcGU7KtLm|s)Db8Ptr*9A8k=1474u{H$^i)q$TkKSBrWK~aYSPQrT4b~!x zVo>?OWL(DINzk zgr}Vt*aUE=749?!TMs2nigI{H?rDhW!*zwvjt$a_EB?Fn?AS}Z50gB8^1R#duSSNR z4GjFl1;`ATt1iv*b+>0oYwsiQZ&Q zs_RK&@B-`(1x^Fz(x?(@?cDlw!xoKN5vm6Xree#a1f(vBgX+xzuw{90hMGD-ZSLB5 z&oA*mR39h1nYOzd&ZYJ0>Cj*3tNp*BuWWO(7&p7|c2L+e3OxvTNn!HPL3(`1lY*|- zdtpM)x;?V2EgR`!dJL=p8Q+hI?5fFLI6pc>M)fO5X0>da;+m?S z)R{s3$yL0S(yG zZ8X{#dE>v(#{a;v^4?oyB&y?j$H&nC;*P4vI6Iq+s=v2Q0_w9+bn)fh;s1)Fl}3&n zBY7Orze)Lf%_#Zjnt}G={r`c{)Db;-(BW?xz-1Ox;?#Yr=wojJ@a)lF@XYUj1<$G* z!wLj-@PNCrpYfwFrvPswF2nt6NV9A3M!t z|EC6(Qevx+wFNZg-Fq~W(m&E5T+YC#^=7o#=WO3I5l|<=eAB#{j#Iv^18#aI0BKSN zLLhRr@lb!XYwJS_fs0ixAny9spDOsKH4w*WQV0QT*6`7=;0wb?;CtD*h*vXikrlP}hNh67>CGxOU7W`8Jd)N0pjJ?&6CxYl zs-v$`i}iM1pMvt=!DTb1CN=7j6n*sBwvn;0@A-IeB*avzPo;N5{ft$I)_R&(hEY}a zUK|VJU(ct_5Uq7sUHK3E)St>+3D^;6Azn0cC`;-M;PqI!jt?E6MOQ$Y%;5g&tyFhM zBo!MtyZvo~0CagPXkY`NmNEbZSt+ibivg5gSEi-4f%l3o0pZk93+T|k--#>ypK@L( z{l9>8pLsawu|SyS4NXCAS16YlN!6K2$-UI`TuW3Q4=W-PK6s6L8VA$}qEWZGv#Tw~ z6#{XoSo8DqPp(Pf)mD?w`uZM_Q)q|)>~sYHAisV?@ZsygWfQGSMudmJ> zq7#dk*QKG;B3l01Qm8=DsK1fy|38r|Kn+pfpge)?>`gOqEqyao$SG_(l!fUQvuAC! zD?n5WgwC>qJi2qhLKVUAmKz_75(Wft^O>6R9Shp*CID%nReqEEB|Xe*>s@(DS)Aa! zdV~fLo9ea-3bR8K^RrI#&Pm{x`#p+YXD=`e(D1jqd9@-FWabI)x9}UsIAaE{{!^g9 zP0Y__E~!`EN-)nCDAtL$wymd5PWRDOI6sh@O57)nn*>vZYCY+ zm!b+hPH%&-x}V3-v)Lg+PPwbQ!6)J6?}YXC-!ZML$94Jc-s7@aVRXUSW=w7?A^PVp zh=*~a+ZXNd>nk-`J@@<~kA<6zpm_e(dRX$FTCs&l(=OlwSe>6JcMH7?0m6g&Cw7-+ z;=FZP{|Kr-8;PMnFA5W|uugP8>L44B`T8nYpMg8}@GSP`93_Jlj$Z~aX@V3*QC-`) z)_8oMe+*`dTJ+yDrQrp7ap=iUu-Z!YGS7aD1YZ9&pspXnH*4%7BQ+YI&a zddF&4V%`XqR#SPW?a`9GetHufIfPvmv9h?Q!Sa_tz=1P1^v`Hayj+qP3rtw+L1*xFl$FrF=`J2)+uFu_QbmHu!@X=BL#_GI*)kEK#6@vyG_ zrGWC|7awTo-b-Mh@a%>icMy{4MBjWRPWr}LX>c4Q0~H8w?Ax;on{!oTElsM@C&%WeiUoj_f9<8 zT8d+NZgKIavEGBPieyiW71hHgecXJjAYTcLQVE8o8GZY{o%@LuInP+38MowA`^eGL zoA_lBzO$!y5SlG9GQOCO^rEpgS*VMpGQ6r=s!DoyGZ@~|9oxlIno1c}H*$`8<(9KT zW|t$EVL#ryG$THgHsZ=NCgC!yD>vn?IPhM!+N;k>a%-Kq=^c8|xKbY&9hs*rAs^gi zwSA#&xULXzZF_1~;Z`Pu|J3gqzwCTYbeC2XgI53c%_K+WJeUf7(@U#>9Z}Vh@tYgm zo4cQEjJOq$)yd-}i@k~>i_r2{+VsnpFoS#*@!s?3o3}>#cR5O}rl;%qTf!((j>5@< z@52He1PfKgOXeD)pXmu3yYBLnF_tso4@Ta|wG7JPKl==eREzc10N=Xr8Hp&r!bRSL zr!UeB@o#Qf;!DSde5a)Mb2R6$89haYk-YqKb#77Z!m*{1MCl@b$4;qn$FzItI0*0hn&p0Uz+66-l?oC$0pzqNja0j!e zpMPy$TeQXCvz&3i^_D^z z9+T?$Dm@b~4n3B`9|2>J*PtiL{)mcVejE>Q9`G-5?GSx|XSnxw-{J{_qz3&~S$JO0NrGbE*!?c%}cHQIC&aHu@Uvvv& z(Iz^#`I{W*ocXN2WcI{SOU%_{8@@EIZ()f)Se^^tduOJ5Cg^{eS2}791{}vZYS=4s zzRh(UQW+U0Jd>}&AOwnPA0~g&g%Ght;M2)I=ehz7VP1vpwS2xm$^*LUNCC{Otha^_ zsQGV#-Y*yy<0awXl(oRI%z}65!e|Lvy|@Csa5)h8Y|qw>S8eWI^}AL@VAhNK($5NN zx-luAVIbxj>QIJT@E@VMhGu273lbRbui1~E5#$;*{u$SkHn~t&?DW**)LpKcow#}R zy)|eQtA6_7+PCS)9DI}_Tb54A{Ul^k-JO4e2^a=}T&lnm;A;&l(W$dT zZYX_a)gfh2OnVJ=+ysZ5JKUTnKcaZHfYZw>V`Exi3RBSbHTnb`dkhX&y0%D3f)%Z; zWErJEgQrn5xA41O&c!l(e68xF*ioX&*n`;&-^fefM2Qx>%eOl_G~uD!jyZrnqXbKA z48IH&lwUb?Ugl^tRaY+sspLqC8?<-a*VpEj?7ruD6fUrnGsD)}Y9D#ffphn$8;41q z$e-%C(g<1=<_bRdqrPxH{!Xk~Ihk}WvxmAqmrj+n$we~po4beC4l_{6hLD4|HUnvp zFW{diye_*l7NS{!2T2`3Gc-$IBNsc6E&}u!vk$$;Ot|0B-@Ja5A#)lTS7II zVpc18`uTt~6S$!`aL@8=u|I0U-v^FsY?e;L>W4>>9LdiUIZ}CoIGmnz#mrXnAG%k0 z%zF}$gdZae$6T%vdY#~K)M?Ty=Fs}P-ogLgSi7iKEUXI1L|^(`3B|GMgn)By{^rhT zSR=WOkoNh+1TZcOU$(ilojleVE8ydfYwg5)^5lo)KrG2A*4ZhjhqT?H3v9AmY?%P| z2-fte{L#Ns7F22Vc|oSC2>vP57M9tOvG744_7i3iLo?O;F)jsJoOMDr*a2J9>$FC% z=uG|J(;+qXix|8s-JgNiR9o;+mi?dWOOX}c{vOnn<;%Jccs9iJPa6(e_2xQuN5Hs4 z>LJI<^V#-V)lt%C#Uk12UQzZ-?K-@vGa2? zrN}bAZ^@VfDwmZm=)y|MXH&!*8_S4vmUl5zpk-ljeS)1J55n3iGb!E$@f=#z8WIt) z_5r%a|9fp(+*hP%doks!W=Xnm@my+J{~zkK_KCM#YcG$E1}uI-+#<+p%zK5puaC#2 zO=tLAgw9{Iz_VY42)T{09!TJbN6oMwade!i7DiQho@EE%BYAoYGoszLFu(%naJ1Iw zkMDA|Z0(Gu8KtiU%6e6mdBs$L&%h&}{sY{E&x>Od$b(xz|EEz&dqbqj+9J@oe_M>_ z+2*|M4a)QuQm(tZyZJWl`ZCRrL0ZhwH>T#mG#=3&)94yr1omOn@dvHS&h8=~*TOWj z(8;-(6vO+X+!}{*T^3><_A8ak*|GonY@L0sI=~3lKNu9|ly|6m?4ect-fzcqmtULH zJCBG<_xINqMv^Jqyx#;&!s?$S@ydHqULr~-Op2UXs7sx>c=Lav^mR4lCngU;PNJG# zv5G5m#(#Q~0pw@FSF^cJ-D`}T)(FtoK~?3KVdL|TaIzp!^3A7^LwBr7uS)BCcGC=d zKPbQA;#ToxAV=NvUSgI={t_}8TaG=YCjBCjS)C?f2T~7r^2-&16`tK6T@@xOr4Gzh z-jI@XNGJ=;aiSi!p($y!Q$PV0=fm#)(M2gBe5YUM4B&~qf&Eefd|$>x(vcoES)A9V z1Ullrmwi0SwER&jvGj}CjO8F$`MC0M#Yx&Mvf5oRax?_8Itxem(m~-OWhrT1U2Vq z=N!r{!~++;@$MA63V|?r2JmGC@~uB=xn)(8yeu3}x^bQ?vLa#tO!CWiey$3}S!yM|BP}s9?zx?tqu9Y=lrM{9Ys&MYDIvq1 z#utn+>H36VP<*EIL$=ctxhKcVVpglA-5cCCvb0XCj|&#F$4g6%`?g5U?tV$Z*I?GD z_X*#5v`!qH6>!YzNDku>2Bz{@(U-|JG4c- zUy$-jO)Bx~pBS-EFK;~`&62Wjoe+7JFO^V!W^>QT?DRs<>&G0H!Rg{-k-F(FlyvhB zIDyQTLn*=26yNd^ewfL1lAs+7?W} zV*T={Te&`hXcs*1!?4Zr@5xEGqo-uAlAJmNV>ZL@0uOmA+xO8gg1|x$2Ty>|#*K?P zErr4@!-(0i6C}XX)k@>d zu`XCqe z{AQuls2i2yI}F8iFey7=QoN5XtV-4K_=?%rT};1mSkl8MggC7yf5xpR>s-9B#bSPX zGm-%81~tAm59cHGu58x&CXh65p)TfOmckF)KRy{RJ+L~k#w;RLUH6)q50>ONp=W7s7?5^@UO~KhcWD zQqr=gr`xpW3G6LjDUfcF)i(`S)`NO+Cq8OjThe!i~iSk|0C-(SZdubkp$*seALk z4>p$b)N&}}cGLr9SQr-lQgAam6e0UNd-DZHr17?4!cM5C8tR-QRH{@O!zS&$I9&E; zQzo9s8L5}9TTkhW69X_b?&&*L4Atz-oyU-}mVTtZNup{yQAQ2uC*+3@_v<6;-s%&G zA7(YaR~*-kr^m4&wbi%Vio!dF4-Lhs+VY6>V3_@;UEl)KAWSeK-**6_Ecp*7p%1>R zHPW)cAf4}uTnpD$V)VCa`Gx;#XSDF$-Sd56&(Rg;5%)4e_rBfFa}^#&Dv|Q)6}C8m zFUUW+S+6r1=^Cly{PN7Cn{!>lF@fWz2>AY>h&P;DbIarU`S4CX_YI1)U0>Kdx1@1| z^zl>QpeC#tcHR^ZU?3tscQftO-eU0-`;kI1$Hxk6KI>VJZnSpSCUe7q`>YVN zyZ9!hQ6_TXTb`8E_Pr(Ae2+OiB`01n)W@E8^;F31I(92b)#Ls5b{Cei@(xK8IO1Dz zkQ$};?QvUeHTuh~&g({|54|BA>QFC6d3W|_Zu>KDCDFsoSa=n%E#*}VlssLoqf@J? zg8mtnJNfy~Xp}q=?}wSoL((_>ev0Dn^Me3RzrSsKbn$0(k5+N4_^#g<7n-u-ao&~w z1T7x*v5fWJ1Qq!=@zF>+iugPq5wAt=pU#~j$Ft*w(a1Ziq!~(Ql3Nv2W0$^4O<^q; z&PV3(W9ejH&BU)tPIDc%#1NCQdA9oS)FfVQ9bSEY?&l17g6 zz5e_L^zv~M7%~i^v1yLZ^_+MZ^+Q||(obD6`~j(DSmMA$@%^xLc+i;@xrW0qrSl$WwIpX0^R=c z6YTH;v;Gtk3IWGvAX9(b<9lkam+PNYPGfs}A)4K92WB~t>2ucZl<+Lg{hkCN3nvfj zT0s6w4PtEC#2fPNF+&F}ZCLw~>BQ9D3P1szBIJW#+)@30c#tc*-c>yoHv==G#sWQ%L7#vw!Dmik$fj>ib zfAn1;!wDN6Yv=h6wPMZB)$`tDfR!edQe#F;W&(I}5Ai>WbpT+-ZmA6$?bdXVR^@hN z3Y@`ikn!1s0S4sBtjqkXZtN53yczwTm?OaWi3C;dMZmX`>s}4k1vm8IJ71fzwPfRA zUV&HnAw-I0#LPLCrI+)ES#OuBS2VK*;u^eXM>2~S%q)Cggkf@1i^i4&4=QjEztOu= z*f&T;C-DVZkZelznuKG>_H+rwH8WphYeOBe0bJXz2IJP`-)@XdhjgrbI6d>pRf&${K)$#u~%p+4M?G30`O%&i|nMP0qdfd+^@wjHobGIhGo_U?Q*A^PDW!|nji8~Ao?U{vu+ ztH{k^aXE+AuLDSHS>EMEnb7Mz_*MUG7qE-o;$owDd!Bz5gVgJsSv0F{iY4Kze!qdA zYN$EPeF5;;G6N4#g`iPu2Z;>Y3kVQU!@z5O2hF9Q0}n6GEzTHk6w;gr{}SM=-+@gK z`t~5;vKvOu?~sSGBq{xg0`42CXP_n6Z}hd-VYPb^7!~E|)bYY1si>H>0goh_(?k}z zH%|q?KBaY;TF^o0r8{!t`_@<2z4yB+uwTaf09}p%cCF7#fU~H||6HcUEA31H&ij|$aj zW(gD*gvD`o zk(15blAY#Bkv})w!i1JyfiKSna_<#@Df0}SHgNOC$0&TA4JIl2K5-qsb%Kuv!F3^!Cv`C-{W?X41S+Jgm6QRz}Ax&V!V z=SH)89_w%%DGHy_0=g-=B^+QV5f4Z>^?@Bkw_T`#9%w68pk?~-i+S8#OoxVxx`f?7 zl5n%Wq#tsXDKzEX;7) z7*qLnPU87NbFS)93ZU=zvBR^rq+BG%e8~Dh!p-m?=DXp}I+NA7pTnydW9Mqh zQQHe1dy9Do*U>P}pm!3XhG?vDA6$7<3Lf*$xlr9BUelSw_O4N5Bj24RYsaAvPDJYG zT80vG9%WW5U3o|fxlm3&u^GjRgG5KSFVwhr#trBuw*R+063F1u;u zS8j)yBLAk@-e+A7(oeZT)P6r$9>spN5T3RP;#d@8m+mPH2^O)cWwS}!d$~+G+<3-W zL-j+lwbycaPwIR^W#aJ;!2)L#H7r9L4CO^{5yyI$8UO>y+BWJSA?~Q5LqWcX*v(zR zFvd}b267I19m(1sVOmt8o#NPuvXor2I%82i_6W_xfU)eJFV$h)Jy;FkO8ymXiMs&4 zjM^K_Z1Tii?`ns_clnu=#GU^B2{Zr~*#LNwyE=8xeH+Ni_kdrsq2NCMGaa>fw^A3? zFD?fS`x0a}5b+V#zY>Jg7fP(szdCU~W%-4jvU}!B1k6qR97EC@M$XBpH!(PG70bH% zCatrTh#yXjs5k0$2RXUC%k`yQtE=ep7)`Hwjxws3WVmJ7mT&m&&!_lU!C;G%{^M#d zhUuDR<{jnhg*h?5ZM1WmbV8ODXgJkg^aZ=JJGF`6P?Yk zd5wn$N%@deP=}BqW>m;}9v8h_*|~FQ$Fvp|q*~gDVwy|k!&M7|+?sLEW{-M>SLmjzy$l%m|MDl(>>1a z7xZe95k`{m_7|NfYZ8-qoE_uT3*f>*UM3TN*!HOBt33%M-sv5#}}L}Y`70s{KUon!a6(CYT@;{vfpGOv{CZw#%+4Mp|MUI zoZ;TPGqp?#lX40S`>}wD5*dJ!<6(3&p7+BNz%DKY?oXUnK zZj||QJb`4DJ71T5pBI7Midlj=1hh%QV`C~@BC(JPhR!BIjwGoO z9GgUJy6<4ByvjXsEXe}vpf5Kzh$7aVpM=_yIjc?|fjvwe=Q!u8P-C>C+lQyaOD43} zca6GFii7HxSitd!7&JR^SDgi0>F9_{Exq;BFYF{oj#fjsR5E@K=vQxHTa>k^!>ocn?o|4tA z_B;oMJm0K@;>Xo}lFN;>yOcm?Q zwm`$XG*y&9*VBp3DH1NzcctgCv$M85>m1e#ySoYnT~HZOJ&>zV7Pf9Zmw#4m`MKYV zV#v@oU&Xz)tAFtdJDEWR(++l7lX*Hu+>J7(Qea(M%o`9p zo_=5#;R{AL{_Mz77=U{ds@1GEq**&Qf-9;{pTp=#HVIriA6fPG2I~hOc;c4@0tlZ+ zTZ1Wmkn65=^Lva70~2N&YbGPzGc5~|EwXLLQ_;t|mfIIL^=nU~RCXX8u3Vy%mg928 z!}q*%?sT?DixPl$O~TrF%>~|d4^wJP2E*@>zR&#t`~mE^8%Ip)hI0b*ktoffoE=!* zbXGVYPR)+A?RK?Y6Nk=xuMw~e-s-y#s)Sq>>fqi$`-t{t67s3v0kRoe{Xl}mbw?-` z6Zx$9Dkpx4zOlL|1oq->I#8}*vn{r$SPE5U_O*I}4cZ)CvS6tT@#tgp7Wyi= z9li!P!coT^d5MsP!~WEgA^y=@xEVDEIT#g@#NOZ>e-|+EZ@Ee6fDQbchR<(TGYBp? zJ$ax@IIS8zn&9qL3cAw#V!$eEaucH;xZPEMm}30uww%|kjwjY(?0ek3Tj3iU&1^q6 zdfAPP>%JUNp8ZA+M#v})NpfgTDOqV<=$S8lY}N?*zvoA zV;K~gDp+Z@yTarVhB>Wfol(DI)IYI&JtKd?VVhc-+{nE-*R7~1QK)5h`1R$3F&D5J zJQ?ztNdevO^MknC0E8?~+NGpvNeA~Tn-me-MEc+-t_;R!P#WrQ+p&8bV9(}CiaKCmM1E@RX9N$c#`0Ne|!j>SPe1$hmjSg4O@@}4Az_qnEO<%^Ft3Crs$Gq~*IbkGx|Lc&QSftpyy$n;y(c$X z!!*5#X*O_+bi=uM!xWO+ZGpm}95K#JoMJ5C2{Dpy`W6JHM^;ytSqnWq4RPNoL)5DK zSE$X23vj{0K70F)h&$MA6$9_Z13y&YoztzMtciCu>^9ns57ap>A#M%YQKA zh1zr&NGS9s@w^Ey1DqF=gnE<4;e*=f_-r7-55*6U;aHH z(<}?p{d@Rmwbk0UrpnyLwT-$uC7KkDunimnKF2q495kFGMZuruz04G%ZpIm!D5UW5 z&V;(1y8k+0s!Q11pR6#$WrqeRR&YA2U>H+V;|a$$VTfUE$pVD4s4tIqrcDCzA0EULMA- zS7)zF4~DTpvjJ6_ZBWAuO?}9QnAmd;qYxyF4R>h+)_+|69SW9v4DvG*gy?y6F(O3K z($5M2k6j}!Az1*nX0_A`fm!UieUC#(WDAkQo0`anJJfU;_%W1dxx3M;#%9}_(q`L{ zwbVX#JnzTzw>R)$f-ssiSB%X<)%!~FdwSlJ>eEzQ6juQU1+`#qL7$Zf>lq-QIki?V7W70ro~~xtK7$u?ok_mrZ9@m65MwgJ-&D6&H!}(Y2_jy8 z{2_LID4X;BCg5QWQwZ`|@Vh&L<$;bu05=GoOc>SJFW*5|OzoFp?Qo=#aNSE)D_nVW zFj^~ecrlF>b8TjA`)EOX6S}J%H$KoqBvwF8{;)SxvS&hrdm;W#7c z7a@y%Q(fSQkQ3ON&XU6Y`w&xZXAEJA<|(OhUQz#Mn8Ewzc5JqDE;NRk^FVB6sWBZR#|I3AZBm= zh%45R#Guf&({ZjUMs5yI?c|i-0+VC@%+iW0ztkqAqTxIKzG3=-Vej{??BQbout!?M z85x!>5hM93qfq4jzFj5dC2)$CP8Hx;p+ErnU#pgF!)M_2Hk5t-Qo|834e(n9)7<17 z5YS20v&SlWb-@+Fr3C-_TXhEr1eZ^<8ojMzQ~4LiprA{`U2sIb?H1T%EY3BDGh6PKr8vp4GpO zp-%K~44`FpTL>{F;+VpJ{mN90!LR32RwFAx+wDbHeujGTy8GEKURco0H?g~@uSgqT z@UuOpZ@)V8ZQ(TsOkU`pN%w-iuGzBmwwxReo8q`ak+rkuu8Fs9eaF=Ie7&u|q2FX& za)0_en5yrXae=SBSlWA9yrg}-V6&N^aH_gP$x`Yjn^P@*9h@QW1xpfY5Zv)96~_4 z#9&yC1Rq+&(U^IgrdimC3XwfB0@#$m(~E*L<~e=jV4E@VXtivd1kJ>w^FCBgg#arv6JR}i{~18 z<2Wnr^^a^U-V1KdX1_7_`+O7%oQP~QMV&{l8|KL8ES zrVFYFE_yAV?v4#737Z&m!fYn_4rj<5Sf|I7 zYmXU~Gt36k$mLy1wM#VwZTa-rEx#=qzJld^zW_CjpdA-|Qnf zHo@($8T2!MdX52pj~PoZ-va8XI1Ezo2G4W{qit*!OKI6>O~C5!!&ngs$WEyXt3b1? zh8qe%zvAhB(BS3?+D;fP!j#FM8?v0qEBz+=0bZP4=r#!kJiC(92xaU)36%BqqJQ^k zOoxgqgi_^})NrxUPDf08HaJ6If={8`7s{~-sIqNy4Ibaz;+KI2zYS1Qi7esm38$OG zQeG$UH*DXPvLr3S1?1h~Kik4j)%g+~6B%iJK%>S$DM~k5^QdbV)n53+L~6tFMM zD?xeaH%A^e(9Q#Jr>8j=vU6cUQ@te}g07Jrfrj)j)2lOeP!0SO2Qc|(U< z@_-r5+O`P+*csaa33U*(sr%+1 zQ_7i~rT_a=K|fHh6$VKF28&-<8=C7_Sq|#-uAt@DD8CEqPG=gVPUDbHGa?m5Pa1~9 z08Ym@G{%`gnul)6c{!=1?BIO6aW0pKSzN0t*=Mq%A~}ppArOGRc>k-+j~eQ0)xu2K zFf-J?0-%*~SIjDJtgzJtJD4DmZo4jO#29dRrLctC&d$!V(9ddF%u^Q6PKA;X9=&+; z_;7t7vchbjKsO>llb7RxDi*&4wHXy&`&K|bp#%*2?v9C@-z zIkDbGp&L<0Z7({^;DD)8)awR182az<1!($fBcO)wS+oj>;RJMNkJZL6p zWq!O!mo|akj8Jbt4!+ zJ_rYVQ-h_pU<;Ak{D9Q*gVNX=_@Z`a&qIH;DopN-jrUg#Wedt{RiK;@a!Fl1@@0+$ zARPV=XKx*rWxKo!O9*0sf`BwgNefD+K`1TKDJd<|4WiQBje>MYcS%ZjN=SEie)IUQ zwf4JyYwi8*WB==c_jBLZHP>7-=bUp+^p#C-3d*9YD@MB9+U*SQv_YzaMxDd^6x33C zz*)1OE2T2EKgf#u$~#OybutB0F<1d%_M?+aeGsa*_#0KQaLmB=GG5SC01cDaD^)U9 z8~FES?|y$^8~d6k!5`Uc-n$QGKMN`GiZ zxeS1{Lh|~1$qovvTe{b)=K`zbg}Q=g6+)Q{KQ;bp_dw>>Os#B3L67!f!NM?8H)sA_ z3!^Xp`aZ^WWV#kJXB6+BZI)aiX4LAP?L!bn(Qxh$N?Md~zD8bq^aZ=e8v2r_S}MhK9;^f614d|G0~U)Ybi6pDX3py-;}a`i zU)ZW3kqzfTQkWlRYfAWEzoE?Kyn=16Kt$<)JBYoypy+#Ezs>&&W$ zGRuwWwb+zPMJTqi`GOKWjZxqHE!2=uxK|q?u#)e99{ki8T=K-93D*%b@?zeztPUIY zt*;h8UOvbl%B7(-ix_)i^Sypx_{mZB7{tg1zgURa-`9$G3op$tk9ik&26R_ z0DDG{d29SjhgixGL}y|M~L-eu^sp`rE$6lGP!RN5-I zrHxY5F=MQF9e%s60@Wt4*oK|kqHqASz~feG4dxGn!33&0fmxT)^x#wWmyA!1qV7># zx=5{`XPNpLhNIuBfD&89gLNTZ`$DTL75?(CG!ZzE=54J+i(0>d)^kE?JPLLRzaUq^ zw1bPm2%3qhu>xxjoaxR!{b>$GQD;-Mt`$CMh?UN_f!)^_RBvXz`;$pOZPD;!~EKoT}H&8 zh2=#otcF)lJIzG9b6tDBBSl_(fGi@Ji0|V1KU-1WaL<2ISBqmy)@mjYkwzxtsIK^= zKT}?BhIBEfSfAJRsvD{2GITowAIK~SQ*Cg*<&N} ztGp&7Q1wtro=kaxv(LN^5ou;>tJrDM6OV`XJG$2XevP0MrQ)nm^j3CXd9uph^wF~S zw)O6!g7M};$?EM`vy;A*)u2JlVp#wpZtJ&Xeya)iV$eiNjj+kz|FB8k$6xaB?(0mE8AmNZZq{{jc+e;_odc>C_0kb%3A=F4L`s%OQFd^ z=T(aSIUw&!hbBaAH80w{B@?>G*L43+&}}ArKVNB*@jL;gVuJBJmv-EMAL)Q#mB3R4 zh5dSX((bS-|Ae~A2;2v8g07_Ek<3jM)~f@12Oup$!N*4om%_Gb>X}q1b7f7t%06@r z(f=%?RH2JD2f@+6A)m%%GxXlh+-}9+2~ph6?xPD197wZL+78Pa{5J6X#(v}0>+d4m{}7MKo0!Z-v*7h$Y44-8mLrbgGn|0 zfzl5l`K9;+rtiVsMIS0)H1I&J$__dqXhj5}>WJ`UY-a_Z)l=&r#(KSet$ShurJe9# zs*cNkpAqr1heoLmBld{W0 zsP@6!Ff=wfcTYjcs!9P7jBd$&8xH9YZjb5B4<}>SV&#uNK>Bm4mm;z;{2>2Y#vARA zXWQi_skEtT9mk-opEk7CP6l<0CC5^QzaA0W9#AR)#>(|B7A2{M1I55Pffiw`7#V*# z(0}ES`Ys5^M#3s+wG=dlCFEyc<8*wN@IaH7t+AZv54=~dw(HypDa6zb2T_!N=JkI9 zv;AQ?%2k3wG+Uf^I%Gk%z3pDdK+_AS!?(PEQE`n(%grMbIVGiE`w@7C`FvX1*TI}e z_AiNXK76a85z@V*atCpwe<6-E>r-QlvTs5#64AQ|C8iO((nhnKrza7) z2sra(p<RNElEVqr790_m)x_c@EcF+m zrxpi&%DOKiugdnyiY3zX@91@T(hFxLY5(@I%bm0IF6j)wiJPO%EAbt@!c0$3Z^Pr5 zt5%L|#Iu=?^k!%6#h-tvXA`@)-Jrpb;z9>`ypZz5vC#U*+ z*yq}fGu+Nvb z3=~c4VFwgfJAF}T{vgCiX=u_nBizj5>68RC1QSmj)Son)bApXmdZTNSv0qP!9?ylC z^Pslo41d8i+EWf+D*7{}T#Q7z>{qmAPBL?qX!pCi)U``XOC#0`AZzAD!rl#2f62d4 zJ7AugfA!*X{($hFjy&oUBvoM36Gl;FB>U`%bmDu6pE+C=hocl6d!NthMkI9l**t0A?t#b-nk zE95Fov>W1wXu0L>-e{vjM&-S|HNH47Z0=LQuK;&Pe$2b2dAZ~sf|XZ4R`|1Iw`YCI z944GBU1%G&zQ4;}tHRdXjVvb4Q+Cz@=p(;>6fs{;uM2`@W5YB3CNskzM!uha0B`=E z89#2|AOP=|ex6eTX*Di#Ve9!o+w~j#_>3iy@KaaMGIn-cE=fPfXioKl0lURToBeo9 zEQhd4hl@eUm|9mG;s2In({ ztNvZfeQZDvMl-H>+xgY7eaZppw5Z31*qQQK3$`~+$S_bPAg$MWoy#3OrJ5Uj|EIfB z&hOwyqCt7$0;(cCn;(Ptl;58{nkLirZ;jCvP*6jpVR~I4&yU9&U;R4cmBQf zb4L%Q-==>)GM=Q44H;~{U8o{`8vX((J2%B(RxyG!1c}`Y0X6uk%Dp5!usPfyZx^^NqwmjzDsX<0|v?Dw&7CJ29wWGk&oUTD>mjOj2s-} z9ph3U<>gAbaXrRLJEUJ|l+Ay`-@#p32hi_rQqlm(&%eO+hBw?b z^PV=%$KT(kC@p8snL%KYq2R z!#E0oJ+{@IKa8*~D&Xz=_KXtw(?7WYyb+n!OTCftWKB|$Y$OY%@qyPr(MJXRHgiU_ zF0{qvsT3oei#Im4L>}(|GPMoq1 zB`u`^ts@jh3_&50FT}*&qJjgn+1k9xwE0%gHf1NXIKIVZOx?68V@lt|cOaX_w^@v{@bhT@wPcD?;{L6mh#wd3K!g9`LLZLcmw_@?0@bbtC#fjsP& za{w-(!bu9Y%jmK1D&fWJ-n8%O4fo|{Rm$E`0MW*ywN*^6UGEKWS?ZxGjTM03jrqY1 zS2OI%>uxzFDss6A)uOlV&}@rcV1E+|jqV>YzIWTf1$;3%cGj)$R64_ZGo6?GiPlu! z1u3W5q)_sXe-+YD^Mjn8tptS)wN+vp>3g}ZE)yaZ**?I!WrkX4cL}m)N0pH{Yb*%a~h1Do0m6p=3QA@L>~$K2ni6!zMI?K?fh=NnSIah zi)SHn<#(IHw94*DE~0(WLEF7zqz#ukXni?(XkLp1phHsY=BLxNK>ieoyw% zzx17l%jBAK6Z6{MEEXSZK3bS%HQ9c6Q<)1D?zjgLS@)VB6M68ij`R!t5lkX{QkIO4Zr;4Ngo*M<}AF&e7g_cc+-YAkiWI!;sT%aDj zp{S?c!#rWOS5Z8Cl}_LI8ob&sT_XWG&hRB+=XIZB;Bz+@uMR&fs+Z|d6U14kEp2f} zLVvd^c2bk>?6pSfEeLa-PYb64Z9>PM=+ih&9$Eh42@!B@cPb*7LTjH?{d_ay(e$To z4WV^UqvVE1B)`Hi6a44%kpkZ|ZQ$nmUv57QoGm?ceZ(YCdE#b>R7j4!MTg+>USIvJ zzig8{oKtPq%F3&gRI|`eBexq}k@1{m#aOX}-{7FJZGwR{yZ+(bpBhvOC90Aq;l_&Z zPG$^SnI~zx6F;h1p8c|Lx@p?Kb#ulh8oK9`WB2$0PeA{}_^4VX0K229A6NR| zwSJo^62o%!{cX9FC2SYTcxOGW1<7?{{Ot0^9N)@ibeaMb-8X5kVj!XMh=99qQK;he zauEN0N8(ToJsI3J?tFB()V1fk<5@WuO5#^jt-dqi6|zfQnmNQ(I(3yCdE`8B&fMdA zv?uXB5?Bl5NRiM>U|TMvf!V#r^0KtB2VQ2lVeKeAZ}fS2pvUp^3Hh)1rxGwQ_B&Lr z+Ml#BZyY~b6kWNSk#Ew%Hb5YYKJH-JurXVy1MIIm+tPSWAC65IDa9)o?^V8Mbb&1- z4xOBCM@!$AVS4P8^2JAWD36TW5taIV1;VXLU0VH@DQm z1rdT^78(AslfQymb%es?rr+e~W43+<7S*_fjj6ES$u+nhvj&S;H=qe>gIfI|8CS%;Gw{nV=<0{iXk<22R zJmq^nAm%v5?aaD3!7Ucfhuc`x&NIKkVrBc!4V@4OVSe1(2vpH@c!ay;748}77*(cloeOxz|(T=v40ww0lA z9$-lxF#e(2&&5qEYl8UC*~G2l2la$BsHRLc3g6RWb;o^r3}?9p_iq!pa|G zw^;}wTKNi#CG?NQ8kRJA7?FYvG$9QnekiOe=i@PNR}Qr zaC3%Y^X^MtFaDTE@z?2ES*2m$^KM$J3I#RufJ|R;MV4|*?TWDF0n)33KJu38CO5rM z|ISBzcrldzM(rl6 z^)?UsEXDcqb-M+3gNL;fPI3(e9}+W=3LXM^7mg>*Q{G;QzZQh{ecMl-jJ)H$pMQL8 z@JYpsTg}+l-3e9=lAr_O-Tjm251OJJOoyzLSt~~0@@eka!!=aPj!S!k(wz#qe_5A#Rd!JoXmW@3zBlcxVjoB-Y{Esh_#7ggv*qa!nH$~Z;qi~beMI@+7 zFtDVOAE@>RLq~!bHc)w}-pmTS-|kr#$y0Si`H3VL|IE2lF;t?{U?mkhBQJKKhZZj@ z)tKedkvkJBD`2U;H=scx_C6DywbI9(tL?F*zVc@hSYcN~+`54-eyXNL8=E$c^>|`z zRo9GLmJbG?DUIAYX}JotK{HI`>q!ch+#;7$!R(BQY&nqR{670>-RyBbSJ) zT_0Z58GzY4)1(89;ja%$RV$>#TQL^U`}-))f;C zcQErv*|UA9sc1I}>rx!ssTeV5679GyMota~1nJGpix(701^fJO6`~LMzBS*1#iHmj&Niof(Hd zGqjE#W4698bUlXf{ysZy8ol4YnF8%jZtt-FL*oX++_2QTo?dCl<(A}K|y^Da-Y{$)Ne4yq&i(phH zHcgv2;TcnkrKjz`{D2rG*aK7Ooeo9~>^905KcoV;)MzlU59&^P#R?ii&Nt4#AwYVH!(<)az^sL$(arqc&msg;+%8imvLj3 zz-h1Nv0h1n+0u5)-y%a&#-LoiH5V#LbWw|q-k znjzrfvfRE|kkXE9?;q<4pLX z7RV{kQQ>Z0d#(^aTxOvIFoNj$+sNQ0z)Rl1uy{nW1ikcI0K~lk9`- zl*A_dZV(wKGa32*q*E){Q-`fz_<{+NuZVB2wNIGU%5F;wo)_uu7ivMGF^xerWbVNd ztQd3!gX$CHJg?HXW8AKRd*Mv3hVFp|6f8bB0HZYt)L2`g*G6%{4tOm`!?hQmpvFX@ zS>x2Ul?&yi=sg%v@Sva7e3DPE!+0Rw9YB*A7=tO({7j!?(X8lPW>r z1Y+WCcUx@5ZbECwQJ#Dj9#DMJQWtZT3u&H&G7DbtS}i5r4D#En27&?IM|-!}(Q4Jrspag0D9>NKfAaqM%~HnND3Cj68{KiEg?+O7 z{Rv;D(#AAAt4}e7rPU(~=0A{x*oGLqcZM3U{8T6bBNqSO?Te#XtifTZc%_}hpN+#X z6vm{=aex$y zTaKGpgMyCv98|Lho?W#stM@?dpsHIQ`_fBQ+jF#Sg#FML&OT7urHGLgF0R;8nmrn0 zpxF;s)Tl?i*7)<|CrlzLA`yD(Hb4#-G|(Q?i^-0%Iu2$T_KuFw`P1pailxox0)sf8 zi-^#B+{e0dak9!{ogk5qOL?C%03+Ipz!_hM#q(aG$!I|aI;ytF4ABcvc@UIJ6z~Ub zO2%sAbUPXA9aiH$9f^vf7aiq(5x(|f5O|w#Vb>O^ca#&e(bHow>32lA12U1x0hRmd z`QM)g=qS&3v=F?`)NeinCoy<_($@<@GUf(g$p$-MlCe)Cc4%B=4LRk)doPMezA#Uz z5aW>k!OU~pv5dK6&>hdWm=&oy7&AWFsNCEF8cRzTU-0UjWi-?M7MPmw8dC!x@Ij)t zm}uI4^AxY0oT-{q+Ql55w#BAGN`5w=bI;Yzt3}Ie4O*ntXm{x~2X_1l7Q}9VkswC$ z`;3Zm$O@B+kA>Ux5pDNE&~}fsRPj1v9RC}^dOW{l3ENFykR*}BA;2{Ufn>H6wiSGx zbPymQV|SpXQTNMJqfKsp@AW0ZxKYh(JIHVf$dZbb?ra6sTJ^}*3HPuFxFtGLd@1l| z$t=U@%6Iw4wpTrPg$;>)5LSB)qTv^hxxWj1?GN=vrQ;vOQ&JR!B`Z z=!lZ-ydQjL4+hL4s3Jzoq8$_q;M>aSOQ|lk-_t`)DRZ;cgM#2iq^BU%iC$qf=w^6J zSVq3rEfMdah%F=Gv%3v2-VH8v9JXav=a;FKEyJSF55gDa#X?%{DmLEO+D;+2`pr}! z)@s!9ss3?e)Gl;&q@TYzP+KyBt$tPuS#C*%x|9kGf|1&tw!&Sr-9&lH?nM`Q8QH)LJdG=~k})Zy z3r)mqKFp_Yx30yz@#%&W5b<67(Kd>>HHS|qs3D20578{AFIBtuv${62X|qOC5yz&t zZLif>bF_7vP+egxeOr+)9iAn5@-W-C5>W0jYE%=+(re&iy~_5KS

q$f~{d3jy>y zVd_0r7pd2?;Pol$~Q}ipib{Dc)!6dmw&=3NOZr^B|~ zF#}~^=0ZtbDrM3+F{!TTN1{wwL7u8?pVUPf%-0!8W2}BYv!7;%N|D})9#2)aeI)wR z0;Jdunc#{^=Rw&xW^H*y?h|@yz5azN+1cZfznJ(zU#}5Y`1El(=Ai&=cv~EErn20&BPE- zneF{xRa@IY7Sc3{lN|GaVD@EJef6S9S?AmrSUG8`qn=NF{S+O;VTrQZSj}p|rVeAj zG8+Y&aXQqND00Mx+%aQa;URMw9DX7BbKu3v&@f424Qpj(I|JVQZ?wP^94#`R_JIE4 z&;;rC)c>Zs_4EADLVSh4gqA~llwXKLiY-pa+SBQ=c4 zwAso6U12e(9rpo9#(NQw%#U=Tv}1c+Mss(c`XAtcaW$c?3BS&Sk(Sgl6g*cIAYC$( z|7>9&aHV#Hk5*X*Np33X-Bl~LXta+%3u$FFSHDr}tP-p$pjf^HPOU~MHXv77Y?v+V zdh2)ZR+Qdun`6MSqMFdRdKPe#drM*dh?DY0g$$Nj9SaAR*WIUH1DvRK+iEZWf8RDS ze7EaxGil}=ce|}24|ReqW-lpt8yV~Nbl{s^;roAked0*gXr)BkYV4OUvl0AatbLKe1~TfQSh`blT&L;aD- zPXn<#2~YWDj%;&Wd7EPeZxTN<7jJ@euj8LdcaEZmpJ884H`@@RuN@VzQ`&T1nZ?Lj z7jM8clWo^0+ukbPlR>(?d4?`{ah%Ln;mga|49LG-S$D%ozbzJz zf%_n+_=-w^ske>%c!r(e(QlLvV@|A}q12)PNPKY_J$b8w40C*phGKo!p5xKjmpby=+J4tOT6z){hlj+sqXiiVopOplR-e#w|PS+qe zGZXIH+DCEYE1Kw+!7>FdyA$%2@C?riy_L*f7uG`@1!kbM~6@gw=1 ztjW8ccB^@WQ-;UfuuAz@Qa<_K!rGnD?F+2Uslk*y!7>d=QBWA$4kz$>;cB!c$MtwC zD08=G`PqZx%@D4h%Pa4#+P+AXOK8?w?T4@}w+L{jk`lKze7dTNKV6ACm0@_)Zp$R< zqf6KGI~p@H?uH`sG;kfoV%c(j?jbV-XqvcN?5rrm%g_H+aR@$9$wMPh?N%x!jFLl; zg)71#idGG0<<8CY$oe|_h(tE|`7H@`PTbCx$BLB81$gSIIV^8Wuh4##PHLq)Z(fn|lwTYFI#M4vR3 z79O00La~Y}Vgh0OU8n68;nyr0B(7`cD1noQ4=yy)s zwA+gsMVZwgOA|>Smp040s5QAL7_oMWWLt&}vXNH$3ardThPa%E9G8Uz_H6U@QTjST zoR%6U{8jS)8||r9qkRUx6I>gi$B9}!AD)zP&S->nDk?;81B&rxWadpqs(*Kgpc@%s z`#)kUjHo(9L1k|3&RlyO%d~OTyZf$;_D{a0w1_!}b}`p5{Qal@)1J1Us8viX0W6I5 z>Tx=a%>T`;AmAkq(Fp)#Pkhh@QCEoW=DJDI^t(N@KcHGMuC~$z&;8$C)ccuGDH#^x zW()f-Hyc~Nz@`!kC~oWn3I}J_^j3wl>*h=!aN$t|zeW7%MRY z8RLQI6JuE~2wONp|Hog?mick3^A=T6{zooaac&0{nTl_GV4xO%H_)L+Lpf**VThg? zGeqr8LC@)SBm^6P=X%_|m5DLH`9KXRULy4mCuLx`u#fefKgRbdBSwMP4SLwo+>i#% z`oAE~i?*Rg)o0E)26xv8bO{lSjMC24-y$`?&Rebbg#BlJ4B%M*f4tLn7DAHg?#1_q zm^Zn!%5~+2q@H|nyzxb%hHZOjf7reD`}vYh)y@_}M2n8~)ehb)j6y{9i5I-{_!H%R z9;?%@1Bi#R|NTSZp-}K%6UbMMHpmLJt#L)i-OP(hLb`l2fu&StO(DWTXlTt95!qc; zNX!blSpQUkwa$53%JR~X1G(hrJXhMS8F&<*asL?vAQFj zE=sOn@UKoqT`XGdn|CsBh=P98W1@+h1g{M0mh_Wl$;FYX1Qx7K_=@geH;8t-euQh` z>ke(W#mW!5z3fpOX~C_>$!BE*|KtKp-aAFJA)avmF?wCc&g1ukgsd`EIYucppoGM{ z{vT%vOq4UU>n?mP6tS;uCA6M-QM^lgkyxuIuuvTDSsuIib#ih4k2F&HuJun(l4{%O zL-kr(qrOtoNgsRxN2GB_)0So5v~cdr<($MG8}0Ft;5`=CbL>;;4bjc9>UGWwh8 zZmwt-9;%{!49>4Gm=fQ5i_8((l=0_KG)qtpFQJ&d=*}ud;6Y zdzV7544a@;uMGQ60#I_oR@AR+a-I{;Dg?+Suihdv^!l$CEs)D{J5KTQT)w1s)GDnA z7pFQ8eO5l28D<$Mvd<$vTmOyw?H(i6WhSVcZ}w6DanpG|!tVxc ztONv)CkFenWm0f!$vN=r&typ%5JIzZC<&#P=}nT1v@ zQ6;5&CFWBus>Z1j(H{V!BuEww6oK~BZRi(Ef`-hMP1Y8m@7^XL@Xk`q`z&_fFp{^4 z#jtmW9(#)guJuc!RlD{hj{ysed$1jDzHp+J?z7&zju9m>4fw**)*G1lhzwMDznl!v zm5pLI#)I*amt{jKy8?RewZC&=i`_?5=RVBpdELi3mmxr%lrnO!xL%$--# zA(~B32B^Y&D}&JS7G-q^S{GOR7l{EiKh}%CHY=627GT4q5<~)3*ZTkAdj@`g8+dCQXWDIL0dN zC|?z@wqH_iH1Py)2#_x9zTafJ0Yx`ZtC+;$e-P9DOkb)Ax0Q|tjsPHuU*)qD?mg1K z3DUs166M*7WV|-nS&|j)atXhK-8jHLii5{4KJ)Ag8@h@sQ-Z}}P)WHRHZ~G$`%Pba znD)!G4@i9JspYooW4NG~)CjOyPr586=!^Bm8HBn;Af6C5ksz|$;=v!Md;`{)6S2m( z;;ZgbThiyMz@FBOi#dQAz~Is`5Ude(h$l9-uG>xcI+7J@dm3M!UIp}Cpo9YUPXt=y z5c07M@N3mbf!$JcT`-GwkmRG;pYcC_~e4X4|)EqCtRv50*Uxdb3$ z#?9jz=hGm-pY`VS8p?qX$KA)Z5JowoOb0Lg2pt+AiK?Bmm2qG}P7!C$#lH%V0v1FY zoW2TP=)XJ$<+6UTF1M{SvK8EgAr#>Dk+2_L>ycr-)j?Ai=OZ2_(b2{BM+p0`e9ib3 zZS4d0J29P9NZ8lBz}q28kWX%FN%f|n2Q%}9gIWDc>T*61J&&&04us6Jsp=fRhFk43 z#&Y8-+CmDS!xHqbSNNCHveWwGwCXPJO!Ehig1GNO*ywX*QcE9hkPsq=Fa(ptiQuaF zUQJlI|9zl%-3N;cy%rGJB<{xDH1{wT;1QFr09yWy++mlDbp>1cug@ZPr^22-G*NpO zmmA-xdorc>A6K87AZgTHxLzu79!yj|Ze}O*oGJHN4fwEL>UO2pVD>3B&JApTVSp+| z!2Bm{=1yL>vb=OI(iewM+(4X&=r`0zF5P`8s?nN^v9J`};BdO~51l*Dwx=DvM}@F^ zLjE^$l|D@&>*8Ag3{2bYSqw19VYS;ZHl##^ZV7dv_sph|9vvK-58C^;bBZMLI0rE@ z608Jf24*i8XfJ$@E^}IE6L8p|B<8ce9XcfO)SdC_LtqR1vfXr6DbP>Gp{d&(Epy_6 z7*ONczoi@naa^cJv+getVq>DndHybv?5n%Yi8`ylbJBUr=p$Ue69WmT&Y5h|GcU&J zlM2?*)4b8@9!DE~pij>p=B*=2MmMwEBczKOiKMH(NSwIKp?@!$ebq6} zhh;4?RPPpvmekNs(sLBs?A386gA{d(+#N(Q9ET>jSsiCh7^m{Di*sCfpUYlOuNAun zQS)KT4wq0k+cD3zhun}SW%Tzs6!ckqDX{3%{4h<80>y(I35*4y3Md?|x^S`6Oe+RrIR@$JGhd~Eq!-_SM(Etqk>dWGfE!w8int|j!!7AQ$yS6ABdeo8USvrWJtAY$p6Lr}Hr)DD+st`Vo34n31atoIDk$VPqmllh-uW8lw(& z^S>3}0Ys$Nmlsf#*+o>SeKW#L^JVBp(4<*j#8jaL?t7z(5 z?-FVJ5L6p0=bt?{g-^b-FsN|w(epO0f7@e?UJ&_;W-^lcz)UeySx)Y&*V4|UYG0trDto)y2j?LjyZa(#yq~}nlzqNXcwb68@QEbVS{0-^+Dc} zuQP5h%XnOT^O1yysEnhQK4k=wSG}KcYMoU^(>MG*Dxv_(l=lpJabqgUhdJFLuh!^2OK1=X#A6i)+GgL8XYU&-& zj-MgbY`Z5n)z887X(?EgQJg;OSQ(ECLX1QN>>ZtCW`ya=R|Y((rwC~|s%cKdBeK%N zC5-kAKb2FiqIh;pQ87>d>Ue}-Jb8}sh{t01&@FoVIU+)dvBL6M2oK6R`?_}>rTN95 z2MB?h_Vi)4GmZ1|fu?MsqT+Muqd|IZ6lPBKJ0si}6jU=uWVmwUipm8|dq2IT^ zQ|mN{I&%7z9~bSFcs-rnivLfg0lk;x2Ix+hmh`Z{!KjP~%_TaG>Klvx8s_Jt4v_zi zL*UTrhqzbinPow_bgG~2=Fv`!Z1nb}8TXG|@@#t^waXcwj62Hp-2+!ZwDs*%pb_JI ziGNGu%E$E=s1M$9)7wnGxzd6aMi3itgpLv!B)bIODdRFNS;eN7tTx!z>Bh7xIV#Nc z^+yW6@^{TQeOFm*P#}dPj_5kpQ0R`&f0UNZxxC(D-IB)di(E-q&VsQ)=7DvxCVY9q z{|ldp62gMN$?Cz~cKkgZ>qN7c7O%WU&m?a6T@7~o7vpiK#Us8*86Scv#F{MGe5%4Hvutzd+$m-8J)f<) zA{AC#Q=nyBc8GQN?HSF%%?rvAhFShZZau=6c+Zh3z-q8C$XKMju9)w2Aatm(j|3t1 zW+S?Abv#6NURK&fIxFqCcT0ak$uq)&u2k47V6KEJm2H4HSe!Ugggy6Xyl^=aW`2lq z>yI|-PhxE`c<&kB&y+o<`|&g9ej|BgbVu}}`Z-C<(PgL0!RguMrpuv0p57aM!R}MO z#Hn4^!;6hW`@>o@B;!o8-ttqT+Qmk@?X$}J8qrD@TJfZB>IIvQ;svo;;<3lBBH z4fuJRyayk7)4tnL`^QHNR_MSyf=r7Tcwv6f?g9zIqZycqwt534lv4R&xO=)5E>0r#Pi5E7`HAjYJWFy@*z7jJv^^j&L0e(@=?r-o8?fnS|@Uts>E4#al?F@D2=!etT;;;?yts+75Uy)A2ocU73Qm+Y~^LV@Kv&3 zQJlS)b(K9;dU-r3AVY%vwj9202RU$V@8e$ZfUOB~C%)L?wLqI29Uzb~f%CYs=1$rE z7ge49WXym_<{In9#i}06)yDmnIJ{NHN~v|7?a3UQS0vc2VD*I~k7MwWXiw~AcZiYC z8K#MQH^#EeD_6$@3&&5w_-B1^O1b&B0#a$mvsWV%gK}7!KQvt3R&6A|S zt8tWL>Q4Knw$8CUmA{p2ZTZi%OsqyUwr8k^F^L+E);R)V1Nj*)Ov`aUuSa1%cdKiK zb3FFl4AkOQ z{Uv(Yl4)^DVcSgD9*MQoFh4x7ucL+sr3dY7?qH`+L@v$Txs2foa3V%$Ow^ z6GIo?PuYa9)7K5>yy}5Hruzl%yMVX0>w_Th#9n!cGx9r|e|BYjBY`hXIGNF>BSNhMrmpp8Q4Cr@lAE!-ow-D4_%R;-QW@}a{QEz zuz-P4{{frzanc&5)ObfNK9_F7?HLpz5xxrhMk1Ysc*C0E`w`{zG}%sajKwF;7L&}h zc<@u397(}Dj-?jIj>zXUWd$3YYx}#I0m`J{ByJK8u?p0yF#Es)Ls`x{d9Y7ssdAcWzwJX@8+zJag<4)Y0$~ z9;)HeXSA|3De73rpQ@Gir^}Me=zJ!MdTlQij49T7)mt`j?}nZg%OrfA;X?k)#%8b1xT2xXI>QAH<&`Sm`l zO>^=zoZ$my*KXfKLZWa+?Kzzfl63g8hHtq`)gum;TKzhwt0l80KGv|e+HHMof?#L0 zOWGLO8aB%M#fkwll6eo~b!61f*zg*MCo*6}!)s$ORkI}Cnmub0=XRfCo<9F0ZQ7Fr zx^Q>wdv{=o?z|x@@yOi#F3WoxywKUNA(0G9WOaC;`nKU3eKfm}n^3MBr$_nw>Ru^l z$7Cr}qHplS@?n~`E-E?UTe_ zajyX9RzbB-nWBnu zg#^}b=O4r^sVXak-j|7m-!%>MUlVgCQjQqHYO`72c-fK1E0}{ZKuw-9Or4Qfj#~Ak z@BwVnOE_N>tIwRr)u&Rsx+;u~^!$9UxJ$w3N)_>yQX;X0kyzNXx!2$ztm5ZCtRlNI zRiPQScnRFu=JR$-UhJ)>qjw@{ah7;tJ8UA={_!~YUHXRq&F?1danJmuP4t5}fRhw% z+<@!b=bNsAlXkQIBX2xOKARklcDr!cOxiDw0B@Lg<#Hn7Y{;c0fP|=;9k!&9UuS)4l1ZJ3G8P`H)%Mo;{u~>xh(M)+PBqMUgmZ9Otrf1oWUna1hDFl zR(jfGxq3?rvT1~qINW)JfFKrfx-T}!0JoK;bO#t6*1|~%Y3gaoKoD^DJ z<^Hs1J)}%qbJWDrT)vo~s_riUTvnZ|oRZAku(aD3@taO*gfjuW8~5nqG;JrW5%JSX zcVGAtwCCIQ&{ggG9L`5-l4_og4bQ;;&w9EKl3?mrXI#%_$>e2fwtn2ualeY^b$&3; zQnM4D*9e45LLkoDo*lIa=E6vU#4}wrt6t&Y+_>7}DTFei=EY8=5u>7py&ii6BA$|y z=EsFuZ%?hOCTzx;U|MUyJ$?r(r{i|b+y(0n)|N&L+PK@B&YO-|F8x)Y>2U_g?b|ot>fHuMIK8(DpHX^P)?lhkXlatC2xGUBoO>v&&f$6heGQL6b>_oM+G7Sqe z0U8pxfLEMV4y5%n3&4gI>Q5TTF5dC&v{L2+Us{n&V8EbYmyVC4xF|AM%2AD5SW=|ih-4_$X zHr5`oeVXO8|4O!)q8#0$K9?1lb08VitaYRna&kC zkM4F#Jz31m%JnfVohYgJkU$!#ZlfG$J83W9v++0uahwJ{QI?II9T0Q>wrdWnSv2hD z!;io+G@QkPp1yYg%fFT1!PefW?aQQ~-kJFD%~Ram{_{=V^&&ZI`Lp=k6s(WXCy=K2 zp6_M*EDmw5Y7yQ!N^`R|po3Tv4Sd`!d6OmLDjANVho6O$DE@r9cE8PmX~`&! zhRgB17zMxjvDEoD(Xoa2TotnStrYpqgvPJG*iQ$4aK7Fuc+wj<6FYULU(C+W@3Nnz z*#u&QGc~6ht6V8l@7tN=wFG9oC@1-(#!3>JgG&4~Et+uiVKCgK;Qr%OtN9C<+rdyL{^lI>fzbI8pqLHZ5Fq zDQOJT%ac2MVo2QT6dLb;QfFOCk9X2a#VJjwCgi51IhLa5K2IxAHOUt)mKQK(B0EAm zyqhBTpc<&zyqL?&FCBO;xEJH(NG`z-_)|wHeXR&d5I_}E?Lxfc%4VNMUldw`j`0r;I zc4a=bKe2VVwoJkzdF$FPIt@;uGG+^7wyU6y>9-8xpr!C_U^}-auH9d-CG@A;`#R^I zbMELL57;2$SKy6_E2bdNit-;P5z@z(J2lECW5XAj;r65(cvyb0(9l@jIjE$P zI^mwfBjDaf`2+`LkOLRE+ZsBJ%3R&vQ)-DTU|Z($Dzc-JW=a5xYx}r zc>%xLWih)(P9JGcwdXCG#8>L}gyVlvw~t88)i?dqz4QU=mGkq{>KnJ&5XI&VnFc|% z_Oq~jMlxY<>p5>FkruDzMD0xYVAwL8dM}^wv}XE*9~-$TNGxJ&6lO;t%(c4YiDj!C43V( z@WuGVr)7!J)pv@=Qp?_G6>2n-E=jr+tvbZJ*9-Ua>$$*=#q!x_wJPdSlQnCWE636R zPW*gP7e#@MoJ8gpY`H8co#hn}`kW}PC|ahS={xXAVg1nFaYI0gsiUps;4Z~543RW- z&3XemVvrxj2G!DvORi{(Q?f#95p3KM-aV4DEv!-J0ZZ%q~+ia?hpzy(blh{*UH)kx1ed4Fz7uUxu*~n zNXv#cIzJA`!l9-^s3V*LWP1T~PZBR%he=6=OphW9(`~Dx%yMHe`0V7-q#3RX~q_6!aqzfkjf<(8TB!?Rbmo;ZkIRU@%8j zvmDI=(9F0M7{xK1TZP=y4QCM=_W?(F(!HpQrG`YTy}mo(={rcJdce!vrZayc5j<$l z_T2|4PSmyrHD-W92+@Lw?`dFVjm*JW53;2&^C-9~qf`7YbOhx&Jpb*=4PO4FSfXlFPL2W31!82M^93OJ|k!4O^NDz~{T0gebE&PjD5bO@A>9pv z!0*iSJjUnqe820r-uLf!EtZVTJ?B2>-23c(?Q36q!V#+Sm+^1nV_;xhR)EWBU|?Lx z#=yX|#JvdqvVT7`3j^a~v4^alha<|$*1-~kkyrZfSByMdHqP!IjJz_8JUp@vmKGjv z&Q9PZ_`9Ps($>n>68ZOgJX}27>|Ffp+}v8+f{eUU;1XUbK7I~iAufZzuQ#){boyr? zehw}$0E-?sHzO|$yi&Gx@!BW@KT*=mhkw=c7SCE5O0R0gq zxR#1CBabwA?O3r^wfVZM2?#Wyo0`0)6B}u&GwI*p)d5ZbaS@_3;t{QKZixXVd-IJ{r6vaHFWv8 zZA?9NZ3LBtJREd=RqVlV=xaQDTrB^-25ISKYXRl~_CywJEz;J^+Re-nTw?pr?nw!H zYTChUEKLQ3e5`G_+#P&Sa(`bgsNN0*TYCd1^JOwn{t*4LD50+uc)5Ud`6Z-GfJ(%iB!| z=3*h>#BZhNA!{ioWPnn36?Acy@ zS6Ocauco`Oh6VVbKEh32Q(8sQM@iiSrD`sxZ4Ne9Lta_fSr{qhF7GU_A?sjkj^I~R zG7vD3mG;q+cGLECwJ;OZ5tc*Qx!5SXJ1XhwTflkUot<2z(%kyo+-}^qGIp*)=KS_%C_YzvZAEDXML}zr9j~C7 zy*j^(y{)>I9+FSi*VR=3rDA8{u4$)e;A3sA=VYa&%EPBEqpIMgC8OiUXXRs|DW@l8 zDeUTvKqz^@E#(j}YXtg6_Ez9uq=U5&+}%vbMqZJRTThnX%0*Ab#aY?c)>g;dOW4ZZ z(q7)$Lf*hrk6Ybb&Qn=NiqG3dK_7h3QXc%HC?lhy>S8CYY=_Wvw^Y{AcJkrkhjV+m zc%!UkWt`NdEd_yv3hIGl3)65BfN6T6bS-VPrEJ`lT)9=PtvzHdcAqJSd!Ezig0>)`Ir z&#xtHZ;fG)3xNcmK`O)DwYY@Az}CL-CIycOGVCE24Sti!*AhZ@5OKC#0xWU=Mof9 zlNWY!vEf1@T?92;oCT2r(%eoiFbkxh8$tlZ>#gVPqvYveV6G+OE1<8Vreq++XT@!1 z<>rn;S;-1L^IpE$oN@J{ks7MX9Q& zTd1IPP`*ko_OkNkJo=uzz^vpfEK%0(^6paLA|wbXFf&(vFC^04O4v&VrR-Fputd(k=55y?aZUXNvB`Gl3H z=o}#dO{CMnlEIXfL5a-|B;`UBXRD%{DrX6?DIX_l zJQqamYv@w^#+|c7Yo;bo))E%J*83fXgkr%1|NG|>Q|v>?;N2F7%>RA|4kgaUn1|6| zlKj^XS11N{0qfH-JiJ(ppFe@bSXZdTSlT1WlaG#2Wj)_^YupzVSBFbZZ+4UzzRC05 zUvWFyG8=nk9W&RJ@V@N0?kN_Wh7}VZQHuNL`0q)!v;&={8jO$kSD8N~a~}GX;^E;{ zdT*K(YQBh0mk2OuX=(8<{Xn1)h^4^<#q3U!f-pdT{!HsZHXt60y%{?zFUu4Ym{gFH zwVrMZA8*_cbV}DM)R3jR|HHM$Z9YQmbnkPe@4lUWB{G~O&wFDcuAqP=MZht2t|v{m zBkBhIJMYbFxWnVs_8)?=3Fg|uNq0sqV!HYy&+pvUDUQvNexzt*lumX>4`J1l%7~3m zMl`qoWBLIh@?dQYGBf_lT5Wmq-J98nRafIwK3lD{C3@+Hmw4<3SyK3H<0tC5UTNgY;4x|_C9yF+laJ9E`IseXYAlJ`x;s{7n?UkF)N3tvp(l;txW@l` zrPzHxS-4T-wVs+fP-^@x&-U|k#km@S{uEy8?sQ>y9S4iO-5eGy(C}kNNx#M|zwTh%UeTlB^x(_NtED9yJVL_c-V9Nt z3iI|n=c$I3!>ziO-5QT&jjm+QtV`4qMg~@OfXQwaqZohME7@ELHF&~Y`Bvk4njg#0cSkp~G7v`IBsFl+%%d9p8oFpP9-?~2YKiwZ$;q}Ih zK;Pxg{NP(Y}5LaE{*1cRBF+pHVm6ji_U0oo+thF0rV>NB4 zQ_d9ArwZ6pPa|G%fkRCpWZB0%Nc-Pr3xzO|^wU8r)JS2wFS72{I_G_RAEO&gJc6Dd z>dGwv<G_04>l4ne0izM8KYI6wKsKs_GV|4 z!{}|ljPF_m)<^JI>?GU|;6D!tI4Rkrn5Nh)@pzA~bHmo##qOWgC2|-Wte?oZ<@BTp zzQlrBypO)>3?a*EKB=)8pqoFHS-R8WO{>>1C@KepfR^axJDpDU+enKe%Z9A@C3Tha#I1t<09$Km;j-~NZD6Yq!( z8i&HY;X-?5Cd0$BS$38hSDJyk$e_AN7Zaa5Ts$8xmneDv-c^Y&#rnL<{W%X5jri_1 zVK5@&h{^R`PWG0cEw$Ql0m`};+p0u~EY1=8d6duo6CNSZ-BMBu|?{OKRS)%?esO$^`( zG6h)){`myauZdQ`SkeL5E@%J!&Rr7V=@Ou?ZvE-&&T$8ew3UWSjbE}|rVv6%{MeG- zKNsR9J-@O)bt0djn-D0DiwGQVy+VQghuK1TAhw_K)a6slf%nBC#KiBPu3)r={eHqy zvKX1F$s@c4OxLE7os7`HVkfkpRoZ^#{^#9Ewqh{EThF#&1V>wG3nhSet&pc2C}y&JYYw`i-!UR z*nRbn$uZnj0-N`mj{rv&f(hcwWnAjpe?F4yvVl3zSrZt^pXpG1;eP;5?Ty4SoZt5b zYhIEG%rwh@R^CtoyJHZXkrDsrBMlS)nz;en7r=v#->|1g|ACTL&zSDCTQ6fjaxUQffHpNG>x!Nf5kNKYlO;|38~8GmjI ziVi(`S1iHijsG|AzmDVo+wcF`PNtm;Yyk+d?8_972hKAF;XGN(IP_9Cx%Cm@OZ#L_ zQ;zj7Zw|X~-!@1+xahVsr;t^uww_BV>IL6j=$W5xeo$zfI_G}B=4eQWlL_+yu*I8~ zp7#7{i#GJrWiR^3F>Cz}oqmF{PtR3u17wo)%DV5E5Bd%lk#+GyB)sW4Fmy+|>sKOw zp95G1lm_Af-14U~Q%Qgkqh(}eyQ*wIGq^8&)M)Vc5q6yo5jz;Q&?vtvHIK=zUztb7 zZlHCO-;Ny{rVohcN&Sz*!eT2d-YX`tY0JFC;Ts&m zUfgs5r?B@mwY=IN4ppgX3Za>d!)ILUfks^VZ=5m`*|ZhqVyM{BknH>JA~SISIj4!% zOfBw*42gi++KVl2U+a8$+~(l6qvbi5fOp61pqGzknZd&pwd^Ld{qnj54GOG2KFwKS z*DHq}A8vBq5^zA!k>*ra+YQB2iTlCj23PB@X#NQ06$Ccf0@TUQH4e7}P= zRxJ; zQ}j)KMLaE(o;nU~Bg<7bEku^(hbJlt82cl<6l5Lq48adEuxOQ;(E(J0Q!Z zwe?c{!}+eMLG5wTHlTfdT}|@TV~Sz&(74tQ>N;azR{tD}sm1w?!x&wOL3R8!c7p;U zlaOI1HQ3yl^BSe>Tjw&9`uM%@sG6fwaE$7s+o|o3KD1}O_F>1nt^(Y=O^ZX;Z}Wyj zNipwBs~A)D?=62;TK<$j^i`SRR!f6Y$Y*oT7w<4a0jt%U9-K8ZGsEM)pgf->$uE_`~LAQX7I%8 zId|{0IL6I;ff=sAuOT~RUmJ$W;*LaIybzhd~PWlS+;YH=N)Q^e7S8l{;*)O&hN2&g$RX} zC#=@^DBhZ4``~h?VMT0C2&*@*?H)hB4CS^DnX76!n;kAq}uQL1e zT#nLKuQYeT%fHYj)Os}8b^9jC7CI~EOhjG&V+<&QSjhjN%D>j7Aw8ynBz8;r3O0<- z`!&UNz7TaA6cN6o4e&y&=8Qs#!LE-ZJMUWded(gXlM4qro&J>E|6JGkc?{%fa2gn?k`PmXoo>{tH$w~PYmbkAei2R z@w#-1Keh#fS$42 zq-(N0{_)56-F)?Da`7OYgT8b3IEBJg$itmFLhL2J58=!)yh{)LVn+wj~Dklh`o3-?8WBe z@T{)z$VJBwWlawVyU30G#=ZP0uH%7>1Tx4{>5%+$D4IMx<#ZwShU1mnL1FlWgybj* zzrzi7f@^nT$xTpFAg0rT$d#=B%1UA3V+x~1M--3uhLPvw7w5*3kd+bB`|Mv{J0=j* z%N6vswzMEWENaglIE025P3j&b}n zF({n0Gl4l~ZK~1Khg-MIgdGqaTCi8Zu~%BWztVoO1%%Mvl~*S9z6v?8&_Oj_W87Z+ zt8AV3&vvQ9qoTARo`B5Z0T=+>6<)Bs+j_?6O}Y`0S3z6kM`zpmsXO@W0smzVB92rM zBqK?G9JqZn*BIH)+Xsr{{gb)cuS`#`|CmoU%>(GK`Kt+;FY>^1d4E~Yg9V{Rf~Ojppx z1l)QNy|RGpPqVnI2GJ2OrxtdTdBSeU^sVD@0-A;cNRkwLY3lwtJHP#KBJkcy(G) zBrYJJgQfs4T)c$vgG!$6X$t%7YA!O^r%b)U<$Qhvk8x*zK0OT_F zEk^Q*|M#7)gY_>%Uk3o2I0k4VG7clX@Ucj8PDSv@tAkwhN`Ub`@FBFJF`{^lB{V?; z)_5~SZa(ps^Nc6qG7QZ14(m(0tqY0|Av+GL86w)D!(jS4Zi~GoEjF}rWu}cBfW(aV zS|9H+bgs`QA)GNlcAuV|Y|bwYJcBd`^?v~di3Zh)ESEz`!X}?$3zF&JE-uM{Fs)j3 z^Zl=2I87b|4T&+GDB`VSwIp93FfG>=O4AyR{fCm0+U|0;mjZ0%cV0-+_JMGuQBV*o7&V7EN z#Ei|^);X#sp?=~|Z16aswKN#9E_rs;`pu`zsP8o|E6yAa2nv#Sw>5r+1#6P&3-5T> zuPqh$seU)Qk|j!M!&^HN)19GKBpz!h;<>^wQfjR9>E3IHF(fcgjXIQT%&D9BsuPKT z4ILPa)a=#mUxV4>ZUs%=+z2|jX;Z-3;_{-zgstL@6SfH1{g4_lic^ty9_|QHUJ{MB*Fp5RV2AYc}IkFNugNjfKndp8vZu=%dGwBvLD567t)*L-NqDOd+o4#AK8(5 z_4QV8%gJ}UlH*V1M(qsgG&~@e;XFCqOn$DC)(xC4sidU;Q8~%8BWK_y!(n9RRfrr| z?T(cN!`+Kumv~uT5&qgGCA=kC?o<`imQ^ zS7uj+UINU1RoHtY-Kf@swcXy_+&qzpQo{djx`?MD9zwTZ0T4HQQz3efJE5&tE@UXVfZbW%^Uy3dDUJ6O)WX?cZx$@l9UXVcjRb>x8Olwhi$vx#`EJ60Uaz zr%oGm7Mzb&%$-x1VXeHDiR8Dnlb>kYuULf)zNHBnsdgrl%tFnE%WT@D@K}1>!ns9< z$qr^yjj*8nHKsg(nx2U@BslgVlQgjVqg!dLnFy4`xw@?Bc42!wC`G`@(4@Kw*|YtX zq0gTvR%4-1G_GiQ-~9_$r~)t+>)KM6AtCo{?V-y=MdV^+91i1n%MG%x>2Mlu zj8;ffZbJH&K%ppM?N(15{Uejfa!Qgd5J(dvAN+g>G)s8b8Ii$M>FuP-?1OxmC>BF{&pfLcCRA|YVKCIg{L2Xf{3{dQz1DUXTZiuS!@QN7wUGm$ z?!oLUZ$DTtvq|J54hRaj%fA3o2nQxT)u?o`l}j&$Sxuy%b3AEsuTpI}S53G>O{u%| z_UEgmky$LZGCbCuEZcZ^8Z?X2pYmXgpIaPz^!hsUR!Q=h)iRYyif&O+QKd%)zTyeR zkakgN{;2xvtQIre?YQtRX_sKQVIQA=|54w+6A4}OJrHt&u_TBxgy||3XT-kGg~QY} zn2N&YB0estkz<+ro(B*$oANjXy@$V9;?yYH1lb63tcEo4$!NZdBlKE{;XfGyP00wh{tKsYXxJNjOJR0^ea6m){NA+nh3;ZjTHL zL*&%_q+DKE^$a%BLKl0|m^ELh@=sn^Y1^*@_mq*s|IBYU2tNf_OFV4lKT=Lv!lx;eQIhH;BqR*~6r2ok5!MF0^Xgf`?s9nk$ut2ADb^(Q&lnXGxg3kEO8GxC zS++(4I?jgdO8C#?480HWe><2}c!NFFR?r)Byik+5IkO$W#z{dH(U9rX=C2VFG<(J{ zGD&)RdeU|q5OXe3#;4f#^oNhux#AvLM;O!``!hCPx2+zg))MrG5|DRi zOFhu)bQ~_$x7?Wn8KCqR0Bl`Z7`92x2g|Ne-`TzulFbK~g~7B~QjsVs6clq$&_8EUBSlryBy137d5 zN*;e^Sxom&`hIEwNL(Q32{bDn#>9EKKc6h7*grcxA#GpUY&_3IPA#<(O0K!u7}+oA zJ%$WY^sfD?>NlB#8B~p8+7w`RN@8~FI~^>wE@oEI@kN#t3HW@!>RkG4=>%I1Ih)j z*+C(z3urDHcceoFZQ+y^(u4)ua=94%ncRLqcafw#unF+KjDTTdyI=)sqjLbIuS^Lw z(1L{HR1}bD*P^0~kENk~h|eH9fcK>G=YwM&Er=HC< z*~G-eJYH*hg&O%0*XJ>Z5+WrJa2M>CwFTbSl4UQrSaJS3*w=`bM#{2CaKRZ?Sfezb z$?*OfH`Dsakc-Z1nG;i7wi&R9mZ!)2ih8|if@*Tn6s({upBQujhpibk*GbGM1|$-k zn$MNvUORs22EqzUkhm0m1(F4H22^R*dXbR_9RPm%xBrb&_MB{ffODE5QYM%Zm}%cL zmm^vvijR;_iG1*joY{JWQJ0O*I)JBV)&X4lGo!aIL0{GGLk&rM-A<6}2`oe1^^oq;AUlAK_wmkSb64S?#h!lNscd3qJ*p8&AhAB$&HLJk(F zD`tb|r7@(CCQx!*3=73ydF3!xsUB$X_TGQw*QXrvXCuLSm1O)(vvmf6{G2j2@k{{wC>T86YEte$C@e!vf&j;!L%iGIhP1I-a z-7`R9-SRvcw=ZK23g7wy)(i((ZJuo8wctE$+!B?{kj~SoQBi{;E!Jf~AIIOw0BVEN zGZ4TIdj<={v&oc>IoWuIvRJ|B%74U?9^57Z{Gg!XHxnneyx*RRrGx0r*2mD|{62=d z?BE_yKImo!9O&N=LzU}d*1F8V(4~056w8IWSlnl+TY;N|9DEHpH1_#EpR64wh^C4U z?%k}wNiG%p4@u%@5Hx7pb|n}OWmHaVe&3;HhaJeKKfs867AOGWl0 zr5}USQiB}#gu&W6?&6mI5iGH;Vv0e_pGwmV_A%zMa9L+mkSmDYetIVg)LrfFn7&s1 zC+U|`2+VDwcookp8zg-DaeZK*`r(%cgc1euy0o-ORE&VZ=+@lK++)l45;tBPKXDiu zfRbhV7DHbDq=RYYnhJ2LiCUkocy#H@Y!Xdq<%rHf+ye0 zK9An{etI}H)R^VBA)J)GvOi*~+x4>HXqEubGEs^Tha2zT_q^O2FB@M4ykWt!KwyDP zfG^R`x=bmem7y8wIs|e%aB`o;oA~TFl_w>kwD? z9Vma;F7Q=Kwvt9Pxa<-2D#=Oh6n{+N{SZb>FLpqE<3?czkYG>~@IW6udURrW2_Mnu zvTgp$SK}jghXWf4+ZG;2iR-I?rQ9d5F^dS%L07RL*!b{J{Huf6G*DVHSGhG1bF?ej za2vp}E<|eQD<$htbpjX8s-7ECZ1_esTpGC|X9y;i3;-!hT*R{=myJ6-tkP=-O9S+> znD~869l?2e=qg-FCaoO0kfd8`q`o)_n`qekq!j+1Pzovt5@Unc4u$bmIb>{F@O?t{ z^}=%ih1jGBFpC(e0lYf1PiFt8x)1Fq?cd41wuiX%lt$Q)G}v#o4ZEhw>z&cD=L@4L zAGlLi{T)|sK^c;bh>-lGJz{+Zi%g36{jQeyR~-rQuNE}p3!CnX!>z79oL*5g_;7lF zR)_%-DIa9*pMbuE)uit2v^SyHR$!I=h-$caNNp(y2i;HDUtY|hm%lPr>-mx-6Vxc< zK)I`M>U~>VfiF4}|5Jj*i&B(-d^0~9L$T`uevTn<|81{q1}=)F5XBR{>)eYvh|3uZ zAY_qQo^6kue@}fs(ecY`R&IPV{GjE+`yX*U`?H?FFpENOuKt5`pkaS4dA5^JB`dw> z@}UI3eLh866~de_J&|v@WzOlNO3h-sTPJpg0NtyJNVV9l-0$;o9DQA_j;pqn{I~Vh zpkSRtx~5%Vmia)a*6oKE!_*rT3K#QOiuKWu|pIJprPlco0;W#v*;z$N9(J zIA?jR3@Qu-9g<>GsiL%KsWeHlw-OtG49snBX+S0x_wng!Sz{uoW|7UjVcCG}fjF!2 z*2PTN@1R)39QTxF?+qx~QJuU$5_Fnii4i||%JfV<(5|IJ@t?>?G>%mzRuC${?f8n> z+8t{t+*WCRIyS|PlS67Y*P{A{lFTRhhf1k?W*SJSC~JR3+=7?hz)gt3hG58Bx?&K{ ziZnpAPNvKZa5#A&Mr#0E9s?nRxPz)Igf_Jf8c28N4FKzh0Z-yFLTzN9vbQne*JS`s zR%I_xz@{I%KBCM4-QEPJx9Hy2`{w~E;(o6|nwFr5;kP2$pQlKcJzVU3@RO2`X3CzI z>KPz?ZL>A!;DGD2*DGDQ_*iXjp~5|$h;nu4%knBopf2AX9wQ#|ZuWeM`-XH`ch>B+ z8%r&4OHJP*K~Q32C4w0OWN~}`LvmvoX362Lx=f%xBxb;DIqL*5um~}NmS0Wz?F7PT z%q3aGUTiVV`Z7@76!j{;1FC_H9I#II(ljxj%5mL@JULdp{jzuk1(2U52z}ia5wj)t@e$|4RAs-Cq5h!2VH|$S+AD=jonu1o^b=lc zhicft1BOpahKb*fv+w(GO1HSx2>f`X+~EIR>zV=5H8dds zGO9JRe{@t&|D9Kf-ADpPdrfxfowwk5BVeTA5z{KNQt-8?8@yPvB;ir9cX8df60ym{ zBd5FCxNkqbMM5k!(Q<1=C6EqzeH~T~q@zN_#V^iSp{J&P#Xo&F0}%~o385XP*Dbf9 zuCeP0)KuR~D9+~m6vAq3m2sR(9?Bx06udEnYh~%w9<*1_NUAbGV7b|8g6H;!;LdCV zc$^F&Hdzt@i6{&1Cm@f1JpW<%AGc1!g10p@0wT++GupRAS@IHT%-aKkAGveG@*+Rd z#T+=4zQnb}by`_y{hloJjpT&S_`CWzHRDbpmKPMkUCBr^j7v!~y zvHL&A#==8fPXVna!&KK&;zNnN-j!`KXo_WZojhW$YLhp520yj3^_5ZU!2hNRejY_4l~Fl|%R40aFg+XH%wO=9)H@h=h-l>flyQDE0` z!dA4_r&uf`R~(BEo(MnO{iHPS`R$UDGV=SJ2L(p-g>5DdT0VDB=a(_6ja2y|d7xFB z43w=!dC)h`Q`acegV(CjO2b9V+^u_`2Leq}0iOPy83bk1HR15Pe^lr_4xM%?IDX!? zCgK2Zp*7XLKtd{;7#+{H`u@bA{hOyMVRO5LvNL2CROLjZz+)-gJ4Iq9KJ9WTqr80wAY|G8I4ye+97iq8qJB+^}b7lQ~J6OS-@j|Qz7MhS0n z$ey1XG%bdV2RItN^Xhro1ak2R8U}%ykx!>nPoHI4t_&8gq$@Gd!;Tzx%)OucR+d+? z<0Eb_zjFR3O@V6U_uXKvj`qLRKUZvWOQ^Or z4QCg4Nih59({jU#)WS*Bb$%**#Iw#yM(x<@B6oN6ewH{62j9V=ZLnkrjum@ z{$={s{L!smOhyJC5v)THqp7f&Laae1T92=ses#GDESw@z{mVlSL%qzW%EEH;t0 z-rZc>H-6N^{gk>M89=94^n>ci1R+_gTu0W0s`KI8zERogOAzxoDr)dkb;;`1J>K_X z|B*%zX<;2@TSW_Z33Flkg0QHsTl#9E-t#@hgYN@M1qBi(}TH`h#m4)UnS|R$sQOOK&y7pr1sk^zvUe}^ZU;Q zHyPv4LqbFI1=?ay(ht*wnO^*t4Q0Q7Fpj2j&d*MRKPGl5{Z=QPF;M#)*PqC4ooSVs z7+;~5C?3~q@UN+Io-!f5zh?0TsF=xEHDojcOc&=1UB!h~dA2Zaq62lM6i6x{HjMK{ zXx;OBI|j+k0nhzXRr>igZ+nM0f0pl;Vxw5pJ{at@4N4rUY=D5v>dR#eA(emH*3qE| zpz9`SDp7LR=B>$Q9NP!YE{(#?e4sW`PV)YzR91i z29$(Or2usY;0L?g{)+Yu$$NE!#rm3n=|C&eL9VJ9iVYGV19a(%DE_Nhw$hV3>Skd= z8?+!ZLL*Kh1`vA4Da_A-lD*LV;!MD8Ag;P&_*!}0Pg)qYm5nax89(||VkkH?1*nG7 zv&R=!X81$B9s9GTcG}5JJ3$IU5_+Xnq40i~aU!U_b%T5(5nf>Y?sY0*FXdkQgVhFv z|GY!n>@iTn5Bh|=y1JspOUvWcFUCXfA*J(Z4#xiU zLXBG3Wg41`kpUF>z8D}%)DD)Jnlb?idK*g}EECHH=;ZTc!bvKfCPi4aixO$bNMSZ0 zOH{nX@BGy$Tsed%_j1TQ6Xz1CCynB5t%7WchZv!Vj~SwG@Ci8#stQOn0lL(*;4rSO zA{iKcum~U?amytLI~^VDF?LIdd<<1IaW>#xU;bD%J&y;RXAz^vCJeX#3Z+Qr?Xo(zDgOJX`^oZ{ z$DnfA4SE5RpdLvemF)s$-@$uordTXkgCI^MK_4=cQK=vaWsm5^yr={A;_Rlx@#0pe zK)E>K{h6reO5RG-NqDe$#8v^UUxX2h971Md@&jPbN0)Bonp_X0UI>Y`!$p)gM_vrm z3Uf}z2mny-swq9ph5I#PKadAY_q@!+v~gr_Q@F|?592bspZn{7urnwS7wM2Bv~P&A;WV0nqLCqFsY~g!Tj{wF(ccg9OuUf0JG1t<95DY1=L!Iw z?M$D2uuu7iRUdq*+xHA3v}tcp5{soJ*l&Nub80l54oVyxiLebJmNtTE0c(b%yD19s z5Nj8DQg~nBH-|ReUnzW{C1+j&8T=C5P6gh0*y%kBRBvN+b7Q1awzbRw^*H?eRJlo= zgA}d*9bC}Qz??`SXu2Xq*A2u29`iO_PqB#Gc*HQF8OAhW_vd^7qn}cRTTb)ulLbc- zDXqN^vA*2(P{8?Xar{{nrKms`6#~~ZjP^&!BEL`22rqDUb}?+F(v@_`URl4RdS*fv ztjZT>6}lwhkwk8ht4wN{#VyfsgPp7pvUD1nxF$RZS=ZCp5L_4^KV}3u4$%Q>V7l^h zn+S>QvT=GQwqUNFl#kV}jEbKB|Ia!gRlp^q<)`{}sEQp8T0`~&qFU=_Ss@Owhld-J zq$na8FOm>?A8aFwld0qfg<-b_&Zkk9LxvhhR56OM%kU1bz>vk6~Sn z_Wq|PyJgxY8R3jS z(hWbd^A4lL3LW8_66<#rp(}w~^&RF{g7^-%YU6&9%z;=kiEpl)9K~M8#S0<2miD9h zBQ@rVBCgEaGt#Z3SLf`aFXU)0Ic2=1S?%_G^6t&Xs8fqAuVt*A;S2b4NR5M_z?Cqp zD9{gL$7lBXr^xmST_BbeF1M_lW=I`fTQvxEJF}6T=r}!ePsLPLYR5$n$E>^^5isu% z*?f~P3@WW6s1=}Dx+&t&zf>idwja(?xO0N)xs3HctC)iB(go&;f$pukZi7`e_$*Mz zQ11INB$;6(ZC?X2u5|7em-7`tS&(~Pa8`bC4V`>e%w$}^Z=4_R@4D{LK?2kYPwra3 z_~!`T<%DdZHUP6|S!@D``54w@D`qR_T%jQ z13oKSGkMo|l(Tp>>?pqrWOunbVui#cv4ia>YQ~tzE5=N1E!yg7*uMBJ04Zki(r-Ed zS&c1rNEo+FlFBjQ1JnhcRk*$7ZE6(sJ3w(#Bo}M>8t|<=*1Z&H2D=ZW3XIcHaq7sh zC1N{Y^KlK~t(jyJ=L?)RwVf`k$D1R0(D!nf>@e}SSbP{dOhFi+dT1B;UK00awr~Od zx_xv-=NLt=&OYqKKvu%G@r7!J;_Q$|cn=6l%=ju{DnA|tWNqZ%Z4M6RrJULKU(E0x z{2o&ZJ4v-Lb-Qwhp!8jmfY>g`6C@l8$;rO&G<+t7!u>1D=f6#3z?&4ogSxr2OBj67=1LKIUU%FC z9=+18?{DaclXRJG3NYybkdZAX#mE74yyBsha=#gZo5$P1uX(^|)hOwy54fIj{Jh#EE^CpritFfTW# zwnGc%ZvcYe$D-tU9MB6dJ$!@q@0Wmmt0-RyS$kC)0xiuV%8ZMPtKENDP0Ku{yGpT+ zh)I830g+jnQENyJd3tVz5~yt2y|M2_VBF5!@uAu*Z)o)O0D7fF3o2!psSk?!8y2od zruWP^XmhGomT^KnhKjTmX*fVd^9iSE=~-*zJ{t#SM8(^-1^O7VT;1K;H{TdeRwR5# zZ!uU0NV`m`JaU;3pOn1HaFJ&gbxrqOzQpF$exIz&C$~Uty^eS+X#;&Xnt5uh%l#Bu zp$Gi$_2wL|SikgjjSrZ_UIMj=dC*jr2r}1hkiH-R9%Z|s2C%TU+$iY4`vB@&v=tQ< zD|bEu@xs)jqwb{J8dWyxXw{a8DCs&G3j%s}cH)c{WJQ6dw^NBbca%XPfT2@h70_Dc zA~`}`4XV@2wo!8q#V-iM!w)>pWt^zQnehfHYH`(Z`^r0Ax_-c&Sohn%C=1Qa-HNpk zi~{83#i}0oDid(V-)A0C4}MPpWs7{R0)$lPCSBCEnb(om*yBNZp&4jUjd1*0maswp43XN5 zu^2){!K1m+&ImWcunv75b19i`xizmd&N&60}Pl z4B;W!dSd@F)pmsgPdr3e^VXINql7WGi88L-kHr{_(~WnVgP9r>W}hl8m24+#tLJ(% z4A*b5gC0~niGSpJw{=VNFskix#_LR(C*|dG_|VGRn)giXiK7>o8C7bzYHqoIeyL0L zwYQ2mW!}U;IE1{1GseTGH`e7#;%I7DJIj~K$$r4_7d0RJ&s&E>7Q6-ECkZie99Bjn z6@q~X?BUb3i5kt&ExIaipeguN@8=C*{D%N5Gu%?`+e2SZMV2Kh1r^Tay#LP$VJOGB z2;P=m>0=Dc%G!Li4Nfoq+u|!Ydk4kt{Xm&tGg{kk`<}c$UJVK#Xdyi?JlA-l3E+8e za|@fbV3najaf}nVE1fa6MnM0Ehliv4imM5$TxMD-9maTSP}{jHF_6KcB)iRf8E({L zY344`(f0I0>o?h6bso`T5+C|5h_jNh;OJU)4n=Je$+#YLEW4bS$I3z(d&SQ0l|{ zrhj>5jaQqX11dhGx3U949j6m22>>%f)04?7QAyA?;fcmTLY}SBg8MIj(y=nPN<=P|0jYjC(gPNEG7pUI8~8zcYZp99(d3%JI_b{g$LMn(DSAt!`%`U zAS9ujv{S@%())dYODpJYm6 zfEJHX8{kLkji==Lap9-nxu4y(vTU7y)K0)2I*;~fEWCUT&_w86P&yNLew zf@Tr8#MxlSTIwPA-UZD%Ld}<(>+UZm<%2#Zc>;blioR)+nO&1>j(cd{tF#gzIa$Z-mMSpnsp zO=pmbeEaro9u%(aoUF*vE3NsW9k>!eT|Zn^W-Z<960eRn|xjhl)Zfm5De z?*wWFKw);}DJ0|pY@5n{K4uNr`prg8RA-CyAQ0|n$b?WxlxE!tb*)7l-Zx(9+V%eL+e%0eS=w z)*C_c;UtVC;?HadO|<|=R>UzLWYa9>y*{3Qom#{LE^c$a)k?V2Ngsnk9<~s0GAu6w zu1A-!0fd{1bRZu%*qD4-r-m-4&SJQ~)PDKIj?nRZH|snRe3QbyC@KkPSCW@}nva^$ zZ4*0dulksLq4kf^Wq=*fRiTLHwLlk_9fclq5bDB(iZaQ_E3Z3_xHr+YOrVUunhY>x z7l>kLnY-PjnFP_wFRJe1CiT%ZK*<6+FMoWS&$^g?;`ZAq1mNMHnUtd2HX|s9$%dPN z>}ybD@WX|hO93I=o&e?aGy=L=SL{B)S-LZqpw=x<9l+2hwj1TK z`PEoFDh~*+!%atds^dSM25xex9p3Ihlo|=6vEOk6sH2sC1Ui}kL4Uxu?0{YV0HB#R zgAAa#kRWl37y|O+k`0BAcvBf=bvqHqnNkW0fhLXjCcpV_8PDBo1Vwef^ym7A>UQbh zh0)3N5v*z7ya$-+SFC~;xJal0f@a%;v1Xe#21 zfOhU71B~pniL@Xe3ZIs`N!WB;th!HY`|VyG3o$b4`tVc@9K0bTt^*)>J)(?Qk}%_K7z8Yv?)Q<#vwSgc zfZZc-Ldb>>-222|n7oB5qrb-l?@E|zokQ~kTEtR4>?#?^ZUULc4rT_*f|>1a?~^)P zsC6c+^_1=k_#e42PJk+YehBmUh*Ds%EzRKoXb7E4b8d(OJs~V|rQ|wYAPcEao(_w3 znh?#z7fVA)@dq4xv}2q?qk_9)B+pnL;1KGVlW?MpXy2lU_xhy?S&0vqp2e`K;;PHF zVVXqDG(d5;0DnHTNgLui<-?Y_f#cukQ)|l2x%Ytl3Q@e8*mekhQpX`~1AQ|#6#^Ax zW?h#UNPhE>zoBev7LW7r?xvc=cbS_44o`D2+6e^Jb`|b5`kh?i`zG;ehw`JyUvXZQ z=6hr{kmWKrG(B=}-9IIK-&t1;7dtTfWN83R$%K+H{?=Z%)f6WDZH5$b0h{h>rXH#VRFq$| z!GK*R!ab5eSKWA1@+_#UXkW$E5=+dzk5X^Oqq~l6!h^Dz5#H8{CqUp{s#?cCZ6&zy z5hs%|j0v|5Eq)Q8eQp#W1^sq28HddMp&*XmjhP<6ifZ0uHZg)GPUlc#n`4-DZe98Q zj=VRZ;YdTUw&}?hA0zq6mg;OnYkd&;<+s!{vE`+}o8^mrAfg}=KMIF%?*kX@LzX=a z+4corGPM6_57aMo%*npq4kOkL!nwtXTi!wIux0)}Y<4vugq&#WD|nnii|fD#9j;^U z>juKAEb41Fq(;PpJTJ_I?MHcr%{Jgv0a`%OXcn8`sQC-w08UOsGW+%0_zlloOlN7^ zG`Bq@Y0^J@K8@IvEhZo*^d|&CT+767y&8Nu2<+;&Hg6n!lcQ{vkxUbpwscyU=1!n* zn%d6ER#{q%P|3T$`C?MoNgemw5jUCz3H#wzSKhlt}sbI@*q(7;(y zs##KEYm`q|a>7yC#u=<1Zhxbvz4QO;?9BtI+`cz(=a>#s$CQkjDMdmkauS&`6iH^4 z3>7lZ9WpCYBt(YHnddQ6WsFS8JkMlSB)|3EbnpFr@8|c=uYd3Lp7-5*?Y-A}*7H0& zH~&6$&H!Oxu_B-X*I(eBdO-=V^aeD!-?(7c@gMsjkKw2%smD~@?p^a~!~Pq0N}5Z_NbL2Mkz@voo(ie)yU zKUE*)ZB{GlzO$)98;7a9d~)H)O}d9i*n`<(N76n7F;;x9X0#D>Si$#XTvyw@;>g`o z%UFAK4<{Ap6#vNK`S2q%CN%9lgW?nQ0b)Lb*b(kl!28}-<&V^mTwi|lv@VE-c7f@= zBb{tT%Gj(&wac>II~nyc6J5Z#H1n}hSr5ylmq)gooc(evX$NS`Xol(eW|+35>n)W4 z;&#g+8T{sGH6H`Ti4~y%$SI8`9ToqYx^!;k7ku&r2C?O_R={C>%7>#e@oM0v-J<_~ zhfF<-k=pt+s+pLNHF?xTPJyXH1Vb!~VU}6K_K<}z${ff|V;Undj_Qpd9`zy>@;){8 zM2a;qhnIZkDEqUK%yyj|M@j>3|`Tt{e8Kp=+^sAsFk zem7deu=x3%gI}=s5-Y;g_&miaoUDi*+N_jmNe~?1?H%_=uXyheaj>?)VV$xhQAuPL zw?!q(EIH826pR*>AaaU>9mcU>eieU{g`;3_5@r967v^i}nk>hN?Lz1KZQq&tD8H>C zI-k+zt>Ba$)FF}BrRxudJf)9@J&NN*y;e^@vpT%WiC+9GA>-#fv{9Z=&u-5g%c0VcYE7w(j)eh|r)5cY4hkx-ti%dy{GeFo*p7N-j z2<#@lcnex!r)mg+OXDYrp>>mBdrNa@#HsU8JjoT3kb~ZYn?y2U7AIXyzu6rnCE}Yp zAVjG~T!F=0^mW9NsgIyM#V8VJ4~<}LdU+{~@w?XFrK)HjoRlHfHw<&a`|^3__*C2N zvbv8qW4#U@dVyt7u>uNVu{k~E~_B($T1%kY#GFa(02WK;{j6)Z*3Ls_xwouJFOiE;p}0N zy#)+^^x-(C0K&s1AvwQtE{*DY%hTR%d`>_te2*0O{rKjin`+$T38K|)bjK+@{pv4i z566;MeY;wAG{>>Kb9ZiOMYeot?}IYN&9P*O7Ywr$P!*T!oL0t2bOg`pDhG?I8lZe zZ2{bdxK(>Zz_#s^p=o*^`Z!?QYPuG)v8~)WBt!06K9D~mqi|8PCdixA+3DfPdtB;q zS$dhLp({O7`rA8CBfNAXjPZ$0gR#>xS;v zMh5FV$Rv9c4JCid=*fuGB?i$S!0I&SkCd@ag`OhyVuPJ=BgBpt z=&oHKBMW!ZRf*Tv(D5J3w4ejrZRClwbaBE_-66{sR30JHi_gm;^A=zo8C`rNrgxXD zzDj53Kmlv5WA4@&=Nbx%gYnJULJqOmYam%+$ct5Qa8X7oCqr8PV-RSm= z4Oyrcj0|tHabtH#I;>K=xu-{p#21+cHYXPps!yP`KvMFFqMa1b*~!(l7Go80v0 zT3+9>K7+s$n-mi@O-M&CZba^K8e0J6W^`W?n{l zw;F-DMohaS;(g=u0!h#X*(7F+=}+^2qa9}(w3&~S^}fW14|6-EJt4B{9n*l4Cp^Dy z_k;t}t?_n+>K+8sdik+Q@FHcM37s@qdzA;e(@8?&F46Q;i-PQn2i_Y$!?%*1>Jl*_ z3=L|f7x0?~8?IDe;#yMv|AURkyJvE=dBBb*<4N%D*2S8pnsf3n6h)K&K`;xluT6Xv zBzuZuBeG7G2+pgGoN}Q}w0XFEPV3No4rK=NQEYAh0k@0{7b2B@8Cpyy>WCU_f*=h9 z*mwM*&dTAVTHnWJJW8}Vj*R__@kjgL|97*cx+?n2{b!IqasLQO=sF&hV@PeygOb|Q z0u{w2fCY~I4=bMysqQLw*B?-zB7(+_+*|VDc6f3^nbJLip(Y{xWw`dc zv7p#k1(o*}*;UE)D`7e&-0*puym8aRfwP?{&0swlp7Tn~D)uq6#8t@H`3Ol5YI?0e zsi@>M_IL%cm4m)*_ll*sDf7nR6WVM*^`U1*k%k7?4&Lof=LW=6efSpiC!Rw^-3)D} zBq)&5D?!Jy`qOboP&l~#Hu7%x`5z{!@vd4zF9{a!o-!g=wJ?gq7u@@L70hgS0b;rutNg`z2IMtY|B_au<>P|r z_<10Sy4D3fD2~KSPp+a1Z#OT90BAV&pSX4DkAUb=&NHOO2%xhoH>0RuV%`nrnFJMBbSoi*1cdw*U)cB@Te`>O zDv#J;f)ZZ|P0V1svXgN=dx*3d6c#QIKaxa*OE8uHwd=9}2S>c=>wZirGfx0;&o#^p zi^bW0+wu&xfkjmlaFO_-K-@fzqZiQQdqhGB9+*7}fIfHsQs-imS>-6$g7!%hf;z$f zpw3?P{U>PNeVuR{Q#WJfzS5ALA`49xHTv)P$$9lz}}|Bils*Cf>#^Y$hiK;XC%OO@xp zn?b6ZDvDt@5507~z|#V{BV~{xUzObikEphQoa}HU&n#^2wa&;?7_DS`r|1<=1%iW~`Z9{Yw z_rN4}v9ngf7f&wo*Km%QD8E%n$fvpBTzz*@@tM6hSII3EsB-Oc$gOIxA4{yv}l zOU}rA?5PpgfH>9q@BZpgEGRpI6dOc5AD}6FjT<-J63GcYSENVN1Pir0_S7pD{}U17 z6xJYre8#KB>ip}+bP~c_FS9cbm!pXkkfL+*T_Y^M-=8dSfn|LSdizQMNKIC54Lt`x z-SGMem=k&~#RoDN0janT!}<>ILLT#0vr1Bp^o{gEg#mBYGyb0y1aC$(11-}qG3xi+ zxY4BghYkJ#&-kwkgufv|ufN{=neuacK6`FU+&3PWZdYNq&?M%|0@~F_6VOuH>}=jI zG^CBa&P+`9G#iOyyI;6@hc?dNZ>y1GdK#n+9)+HHdW(xAUXXo8rYDU+W za{%kqefm8WI#^zHi-Qywt^b}FhWfWg*8hKce!|u{hp53T4YuGGv-fb68|MXHf}{MB zwTBj`skEoWf=zip5ZZU4rN;H}*H1KiVEx5qYu2-N4M3Dip&c#3v~Fl&KlEqmpF=u) z2!97;2jP5j{o)@`>?OT>KR(MJP1~D6+4p*hnU%m)9f)#xcBl0=Lbs7PV;*16Dt^qo z!>4iZW%SrdQX!iQDNhm-yRhW4=ziGBzweEMhV`O}kYsBoYw=|uCw;at?!V{Sd z6QH)WV_vxvO|~~LSQ@IK5j(Nf4rRf#i&MG0wku=r^K2%SBwW_b0$J6WaUr+mU<1?g z>vZJ@pdbQK3W3E}m&vm4*ehJYlf;`~{hRD9C>3{5f1Tt&Kg2sqqbgfbSVl$dvhHzG zzm_o92V~UrEE&!^Kyv0***|AW#yPN39`b^5o zjYBLX=DGKbcJ`2}p|0QmR91}lEmP177X8(pA{qTp=&Kff1DG%gl8`3OfE?}HsrO-y z(vKiQB(U*QTq*mUD9_J6Z}kHLT60QoYwsDw)t~+3SLQT#w(k;VWb>MipTJx9BeVs~ zB`f119r+Q9;;!k+17yv>39?}5$tOe>omRC<8}$H@Qw4rybMg;o=S?;-n?I<7ETZ_} zK(e^$J2W9YT9;i_w9&;V5p)EYIZhMBHs7Cr<7S^q9`!u{ysIl##ZObuXWA_`V+6_$ zK7A632gYEW9xH+iA}v65G&X7ZDGzItw(^i2$dN` zUW$mE>9V5L6(erJb6YB(w#n7K2bbp0HPW`3uG$l;nFWND9ia}sJ1yFh8;Vnc$CV1~ zKMcHlOJvP$tkT5P%%RKB&5+uF8Ay<$07GpZ4sLQz+rtMW=IOnHyf6Nnw4+Z=BSiGY zM#F{x1%4=$1gshRQZKv)*&7}uL4yiDgu+Y~dHQw(8@M$+gIymnp|(F1WOw{x;zt!! z`q5F!Yr|nL_5COn#V6+ZLN9P7*oA4{kRJMSoHcvA5A#3lxq1We<$NqatOcRjCCj0o zd$K1n%|6q_Up+SlB20Nn92hC&e9!k(OS~pM|MTh?q4>DQ>rfDd9EeER^Ef$TD^q%A zJrC2L>jfcC*Y%b6j~wG=HQ4eU12d^G5YzDnQ^%J8ti1|y%4TRUs-P^qcKJ@Plhx?2 znehjd)80?p>MYb7Ay)ar1f#3R4&aw_^WMX_o;*WP{>MlA9F=y_y+{#o4i_S$@-_uZ zarZZiFIgvn0|C+^MG`RIl_aD3w;JKhz8c}O!tDB-m`8i#`TYuaIn5f%V zm&?Id+q^qHoLSOoxr)IZnyPvGebg^s5nsy9Z^Pd<&K7jWT_6PV&xHGZ_U3Qz_mxbpr-a&U zmWviCoDXwz12^gvlatOjEsm<_c^Tg~ixTH2CI-8XxKo_Ge?WcLqLz zC|SF=H&LnkPElM;LxV!d^9>$aP~HeYKSaZ;VORz=Cz!iua5R-*Q0FOMY18n zfX);(X!hw(K!@nC;~^v&cmu5QJda(MW9o7EFtC-f94LA4+SIn?rBEI?x_Vm6@(hu( zI?sINxh z|42`(N!f98;YPr3i`Mkq-a*1`=u`8N{7Y4UC>Fq4Ci#=!V2<%4YImdH(h3ll&dsp8 zk*GO>2RUL2ng=HA-N9OiQi}^W|Fm_XWVtqw`)R;uMvz!XX`t{(|B%*fzFb2-Z&m*P zbX+4khO$av1G(|>M@x{}haYhUqQ`9z*x7(00G2Kp4G-T1zsKd`x&=@dDTQ$#s$qdE z2P{mXw?<7z$DM^8Kva1MJ&uTn2=SN?Cy=z6@L$aXs(=B!DF?zq1R_y02-m{Y!Dc9S zjiy8q39)P~0xOSjBJ zqxBlA1xDLj`Qkb>q8qTNz)D-}4k|^>>DRjLnmNg}>iqIVyh% zO#(TeDCR`;A6dQ;_tPi>pBy(JhK(L~H4SXwQX8}04r>@{-#B1uv zulVP_;J>cwEIe9y_iJ7fqSt*gtWmx^b$H)wWm^xq)}a|&1<<_at$!>9gkPo11rZe9 zq@)CP9#D3(WGh_}2V=JNwMf(0P>?Yw{rWzBsHU07Dbf}iOcl+`jPL$Z94LWgWU_eJ z<2iJjy9&~fE;HHWCw{A!Jt;lGbMk`Sn&IpvQ8~HKQ~*rrtH&~v?4JwbJ~#_BEqi3v zQ)SFKr*<|4eRKgZ6p#xQQrop?ojSo*E}NE^Px2l@{wVvzjbs1LMm|WxXwvfXigOB_wqiI!`c1WWmt4@HxJ8DI^lz;`?{G(`q^`E}-i~vm=tB~WT;DdD} zYlnLww4EageMged`~We6#aF)=Mr99G^c`fTgG6@rokKj?*kPu3L97x^Pep8S(c7e! zW{NtlR}ka*1ui78r#$cHq{!+8IuK(qSUS)ci`7{8>ivcGeW6t+_+oJ23|$vRxlghC z>hE0Bg?hfBAh5k}LeYO)kmW@F%TX+s4dV@PHOk>muHjoFP zSwWEC^b|DNX)@OABP(O0%cFH*+pvK0*<$vR?%Kp(#gjBfnER_fLW{^!wwdp1K=4{< zL(z}-;53a+~9gnE`q0HQxgf)b%{n&!qW=mh@_KhWQB z`F#GjC$Lh>*RO;YDU;LpGbMJJ+mDhDhvpO4UGqmMO5s?QU$6P!_N$&5)mC6rhXmJ? z`nLNYd8H6CEtm@nyTW-To0o2$zyhr_&^-u5(n5K<8vS=(Ch@5i_PFPy+{p}ccL!(a z78Q-fDP>b*s>mcz)lQ5;dOfL->f?Rm`ysEcjXkGh&-B8gBHL&8`pRi$jt9Dhj6Vbn z7pIP;W&nyx0%u9R-+6bMFc!_*>JOk+)1<`~Q#q5yo;VxG=g%LOZ#^RT_!4e9_;(ShdwZZH<0Yp0TZAZ@V3lo|V;7Sl@I$$yBbs z$^OU6SxlVAJ-Rt>0yKsVj}IX}P9AqwN84tUMNB}>Fd#wW;zmfYVzj1bGSe-X z+aWuE?YC+Sryt@WJ#)KXI<(F-)%}jI-g1qmvT3(zKw;awpuP-e()P6!4?lF;dDqN` zU#K*Tn#h)&GhRI(ti;4Q5KFNB{uy!FkxQ-7mp*>2%2%x$v>6s@Y;G)kc-rri`bkka zRcC9Xm33YI6v{7RO1_`lhc_Z8tlM79m0$fDOg92NtPnQ5%lPGEFhDR$^kPq zMV5wJqg82>Y26D|XWs{}50@#~mVEATy79`dEm}-jI9m`V>W*>77UbaXn2Sq(9t37Zp6%`IASUQ3oEiyH#y z2nhiKv=DdolPIy)fP7&M>%u~t9;@&WfwIA9U;dP^wc&>{SNjWc^h26dYYKJSp+F6x zNMgLYVJ{!=6KvO20CG`!*DO?)`V&_ z4e6f8#IQINAZL$*;Fss)iTCFk<+kIn=+r}up2zn;Py}V!RbejlD#r1X$L-*I(UNMb zwg)91uAcs+En1i?ad9`3|O?e=C|wO-Ddr%dB~&ETjvYxccM$yJp2 z3t1c_r>tU69D##oEU!G@l{PLL`r=c~bSt%PJt-BAlV_aZ_q<|}csq~Jw++IETMESl z@BDcBQI4L(W_;sB{95eFgthLso%Q4tXG0}bRn=Zo<<8E|5Q=2z7TUe_0)tC>mQc## z6=&PWr2{ln|0`U!(5Xdn0+-j}u@lRiN8hmVehFnuuMrj!m9r30c`h7VRu@X_S2274 z7at6G01Q6X1v?re%qH931w z_OAuX=0S`M&EkX2JLzdvyz9{q1Qo9scustEx^7n3MVof@I(onqrVx? zwN5|zU$N;ru2&Yud2X|*itcq|)x)W8&a7k+&Lw;K;BVzUbheA!ZerdY3&gA=71$Pc9GL*CEt+94 z=Zd~47<;J0zW%QMAUSc8)J3sQNJxdmrX~lqBj|DVqStnPEsrlmj=ZMY+TM z5x2LS!F2jK0|UcpxSL7>Ol4ZPK72SZvvPy*io4SW?yis3gr zEG*K~*1!_*1hDHwD9*{{!AAM{rs4iZiFt(|;+uW)a%g0>HCjNXme0&ON~l8}I~yKe z6{)JM%+HGIj<%+x1lzt->^Ez@$@1KH96l3lL*pVan8&f-OcG%X^ZEKWaQe|1A3pNtq03j zK?a;?SQRwOr|9{BaW87Dxl=;YlGpTQ{`0N3!K*a5#E!~iw0~u1D5451pTsu9@sKO( zf)kH4F3m>IsuOfGdBk+2CSE9;otc6q97vc-5(s{sQQuS|ProM$1oF4bVO*wn(nx`l zorT5wbr_y7@bXgD(t5#A*=49OBl0kYryS_;KY(|B4{g>c=P$F@qo$55hLp`>Qi4-0oDPT)UzbtsQn6aLm*p2h>)22w zJZtlI5k*^YpD4{{SfGCUa*pIF3h(jCgofSH@U*Ojg-BQ;lC4%m#nN(A7v~2Y+ z{q-yZQ{L`6iH#!B@VzB23Wnl0P5Rh5?&4SPY4dks#5&Tv+m0Gf5DUbA?$i5FkixhKy5 zJEz6ezr=S(Hy^o$8JH{?v@{`B*U!{^z1SJbt)H3-)+Kp>ZIKhs+%SzXIb7Po*h4qu8x;4pAha=BL);8UIW-w0Y7E5ax z9Nr*HI3KWp*6TYLB_N=GwM(tJ4PzCB|5r+c$AuA>ls>j0Bzo%<^CC6l(VWF=n5;7A zlRm1UU8erKIiFw0SP@^25u70KaWJp_~>S%!t1F;1-hsDPx==oXFGRV5UE?eI!3(z%?T%}TTQ~4s&B3s z6!#+nz7~G|6I$ipa}fPB;GwPay1hS7j@TQn75lmta^lNOn!3yuhx2m12frop$Q!G*UmdLTV!Hvm<-)R@y2n`CIs>a9>*j)lC z6E{D0ER-~coh#3vQ#Jq^V4dTf?Y@Exx+9pAup zY0=dT+s|LTxYM@^LL6Saj%nt4C{eqTMlR={fxCfc+GHz^6}E@F6Q(EOI2NfvE&xMB zJPJ_G0GKDlbIP*6sFkPDs2&YKFEW9XkmvSXS0Ca&+a7}IVfK3o`eb{-phGO<>eu~5}{HIivi80IE=YV08=5ZpC;Q`Oge zQe|;Lk)SZ~WA6SCVvnFK1qeGeKWcV0rX@3CKuK*WGm2;nUfF&UN{oa)TPTuzBA4#M z79z|UAt51=%nI(^r#KT3pvaki=2*%r4!}aQe+(ta1>FW(4^JFu=lhtSKYeOc6%iR} zUUfZ1mE}4*^|?UJ0>k8&vm%)e(52#WvuHoyqk2Eunn{|oVwUXxBbro;buV4=MGQ=l zjsc_UC+R&mq_~*b1OMeK$gQ5Y4znNsaoG&fae@5&&bo$}yL77Rup8K1zk$2UkW6$e zqouVq9LdYUR&rK}ps;}<-!EJ=^9-%z^XJd`D;!dGbbN?E%pN3a7r*Z$!1Py4dpgm; zih6l+$*z3Ru2Y4_Xl}h9S{TZRv<6VxFa+_voO!YmbEWa&e14+os|UUy?*4fMoPHdm z_J-d*+~?n2fjmW#%eS_5CI&((aX_>_%&SkUQHNKyZ-+RJW-g>iT#EdclshLHjTIHm#yx z{LkM?)o|O`+1{oTGpHLYP{z9Wg_{?K>d{Mca(vFK5=3>CvB+~EcnTY62#88b52)WN z)$WE%{$9$N+7;?j29+7LJ5R@$CXdf~$xJ@MTNHxtkx}fAmgeT?AnghexYw0qd@-LK z>2=7pWw&`ESf^#xk2_j5g`Z!jUe0*(#tAl%1QT~dbgKQi;NSHufhPf(wJk&3hlF%G z^7@+(1*~*31=zZP^hd70uz(Fpc90x6`+{KZ#fj;CgbHN{e=wUdm1<`)_8{Hd#QNrY zxs+~St@O+Vi^A}g+`L25oNrU*JPx2lY=nb(2sK zfSr#(R4X9;LzAXP%Es;jSWmq6S52YZC94e5cs<_I(qb1?o4d9mTr1RMqb5tR@gef+ z@4^np)&v{drBW1H^XJej!`u3sVtK}{MfV0Pl|9Zn;STP(Xp&PNe>J%o) zxm=XUzu{ZZYIbZxW8TTd$78O|1KvzAG4)uq82VZu{Hr(?_~-Eio->&5v%XSi(P28F z)z9qjPPD3BZwz*KePeMmfh>l)Ot~jJN=?RamHLeH+ zyGcjwN+@(%u+&U(1yf*gEWDH6f3{XJPqU$%omLKojg_0}v$}WBheqt>YLb&vaBVeE zHA^0AY<%|eDc_g9sz-KG(~`~8X)T@xC1G#n)l<5)K0I@;poaq0N;Tlm<8ld5UAL_L z0&VjL;mYo3AL&0uNJ&WdlgB0rUVCJw6H|72p@W}`voii7^-wI2R&uvX#wGJ`IyStP zR^aZR(ab?xl0;S~5XFsI7DlTU$E;5M+`F7%-#0egY45i=Gx@bZ?_5N6fzCM>W~MaA z^8a6TW(nPGG$~aMdAU&cdiK$`Pv2#_sU4gZjuo&H&ERc3D)9Yi>0Ipzd1aegAM?WC zGi1C$I6MI(>Tvm=<#LJ`6IXLjEah(IsO_)xEv_y9ol#-Ut*{BM+3rtYu@*_v5u%w| zh9L>rN{Xtg4pGr->{u;4fzro6(fN`-$EJ>Tjqibj=h;Pv?J>F7$8Il@yF=SiF=gk@ zuoR!(jWjQO&{IQbS4z}QAbR-PpS5ro9bRf&>~JU8Mx#0)Em=oe-`cEqopj7N$UlD?K8<9tt~BYHCeurp^D*sEh%h0_6t7$G8mCL6{9q?YGHqlxth{u ztp1*Jc1luTuViYV!rC@(bJ&IAaOVW5=9<9e>m*{%Dq=NMQHze$(q*SQ_gx+Gl)6jt zN`L0`Enefohp##hiUNsVnTff#O}9*b6W>k`51iBQ+1j8xDOT`}c~dGL%Fi%_R6uX& z#tyZ0C^)OKI!3{zqs`zAYXS$s)I7j9a`IvqA4Z+IZ&7H$><71`5vjMO9>e^}Ex1Qy zp9W|Rj+g53CXX11nR`tzH*HYfvS_7^l)5<~w1Hf_X*b&;2Yr4kuW6t;2EIFLsgt=m z4ei%cnLT2eN^%@jZ1_tF@2mFT9;<*to3TZ=IwaYT#xp4IEd_mUYkxn(XSR26Fp!?B zBeW$}%2mm7>77ho@Err&R?$@;az;s;n*&&E)02AT;!ImnISH?S0*q?lciJcW`Q#AB zx^C%7{;-lzo5!!^*PmtIbqR82#$RR?mqjXNsF*Wp>FDULXTr7j9dOv%q;z+@-tBnS zRTl^=B#`mrZ@?7~m%x=6AJVj?yWaDOcA!$?UBgHUkD`G`)i;4Eo$hp-J08~}m#eiK zo14!idlaP97!VMU)hWte&_wRK0(`hxYHL8_PUT|B_k)kf-^aj9E=9efxbz!c{6&OB zvhBIWMVHKEVhrFzfThUH{t~%23~t)Z`P+`Jo z+3+1l|1AG0m^1zO{;DUlH~tYs7O9W~-TwCeU86dKV7o=QtpTuDGp%FYP&NLj0JWS6 z^mT3C(_L=>W*p)sirD%Kx1K(BOc83VyPM_X!RIckgDk#?fy{L#-mhhghK6PmSOnqV zAM>5&OG@FK@Pk(qtP%^IeF1N{zC4w1e3GXroxPo()bs$01|cSHmg7$-uA$*ZofJq} z0ZeG+ORh3VM8FEO&Dl=*b^VYs^BlNAAnwNyG%*pr_|)AQZOT^wt0a7Tcv(e76t(e0 zZ0ISVV-i#Sjg1r)Znb+##uwrh=y==a+Dijvsi|ph*EHn5P@TEQ=sB019?1%a0b{=CvV)ikq0{PG@yeZ6nnVDB$zC&jAQO8 z`$fbmITv+v{P@D-_4lioRLZLd<=E!XMD3|!D7rtNqm6Cv!irCo1Ks*WTfIa$2lSlrAHg1_uQZLYE3NSCSXvZ4G@>fr86mNuPu{% zz=!|qGpG)dKU*A;0xTG@kwg+{pbM1Wa8lUn4!40Cmq@r8*Nb}Dt9K$rc42*y!Uht2F8Ds$Z@;3bvA?t3C8^aWTcB)Q$G z!uxRz>0K#WxhFH!T={V0XrjD3?={Y2iX;vT0&w=cb0Pz<_X?DP{QJWR zZiyS)jx%?hw==B-yaU;cuHXqQsDkVEmp^P>19aAqi`YNsQTPD`@ zC#U$>cl{Xa+-sD5-*rbaMPE0->Gb_3t){%RmD%u(vRK>LlOpAu zbw%XUMnw1EYwn|M#Qz>V{5xXb^J3SE7IzJ}qO1hcIG%m3jx?1fi~F@?)s^LjLi0%x z?Vn9pTy+FmRYkOQs8ZQi<>BeMFXC_{H!4_}m9wgr_GV#tan)Y%N@zyEe}=h4aAZQ^ zwSa<%`wEA|ddAi_;>;UTiX?VMOguH*I(Sg|R>{6K6bdV;M<6)ldEoUULYT7v;!^%)J-?)O2 z<-idC@rxac-XyL=}{Mr$#;`V<{Q?0%x6#{JY_}$ z21FO$~RondUw1y=8Hb}* zv0Oihi91RR2xmjTehQy0%0k=P5GAm|2cXZ&{SzOWCq_&ND7)`ieG&w*2h-OaDcz!_ zA#Q0FNuydbIR3b}xL&s3DAu}f9y+A{>D~+W`@%X(yIp7L3=g=n;j7>;D2La>+N*J~NET6*jTnyBb-4vK=gr z%@^iT2-tVl=1`ED-4>ww6Kt3S0u7bAVn%@r3$0xeTsVRx!GEIa`&E4CdBZal;WE`P zAmR=mCEY)uVPThWL(56|#To}z3RdF!!ZC(FkHp0>qmrY1Ki2q!s62(=y>OcS3MNEUcl`c`b-#>#-@zjPS|APy~$IT5Y+^ur=(zE-iCXOu!eOZ)p z*sg@ANLk|n6+6Cz@}Ez4J65gmS}@v2iQPyUh9xNE(Lb>?K+T3P<8F4Q@{fg-#bq<> z@!v0^9*lhX_(<(Xo(32&wqjQMze5S@e-3rYcRZ`{)|?kvoKW{Gy#s&83hpgbHn%E$ zZtZNt+8C_TWBK!+u-eFXTbiW8{8|mYz)aM)UhzuN{`1`go~y(!Ef|ML>Ca1CI1D>-=|<|gzkiMt%~%4`jaylo x?}AyS`hH3o>`4P=1w21i(vxl69}=qf2)h-kPCnG)UnYQmigK#5Su#dm{|_U5$2R}~ diff --git a/controller_manager/doc/images/rqt_controller_manager.png b/controller_manager/doc/images/rqt_controller_manager.png new file mode 100644 index 0000000000000000000000000000000000000000..01c4f55bdf1021623377c893c95e6240d67b24ed GIT binary patch literal 49114 zcmc$_byQSu_%BLJDGE}Of`oKP4`qN#i_+cQ-6J3!N;iUnN_Te*ox;#Hba%&n`L1(* zN4@vYyVh|nm$Q)Bd%yKOpV~q4vXXbPA7LXQA>DoR`sF($Bve-l{vQ2St(PZeTs2G)WTJV(B{XH&dE&H4e zf8>`$x8>hI6?3lDN{o6sqZr~;BYT8^W-&>u%0i~eFp(NJ`-32d} z^~3rneON>Q9UTKLE9+JR1@t)f->W&GgqD2Cb76k`_;Iew-a;=n5#xRP-GQ$kMkOS# zzG9yk)0!te-^@_WGUzmqNaOz+DHu7i$dBaf^MRVLD;ukP+I(9+Q6m~Ezrew&c^ zdtZpnp^*fuwuOzsS*? z4R#@)Ky!mJwM%2SG-TO1a^)*I>%R+yObmUeqyw)oL17D(65k6vj7S!W#t)y(t72&o zR71KG#eLAR-}8XEqdPgS{GWB1Q%H9ne5s*LgFL94nx?ANjE&^p&X8gL`H6?i52P&e zBlEx%SaB`u`^Xg;$&G*Z>*-^T+TWxO6)61P_`Z$mZ&Ss`e>|&oPfr)EF)$-TcTHFr zYQG)dYX?iF3H_m^(EnE3Kq+0W z=w$;c1YSG-tAas*ToH9DV`XPEF+o_?k{z64>J%{-X@&PcJ`fmUFGAwef3p@NpNsJ0 zx8&E5hXvmpeAqBm?L)|i6^o0dRauDjExkfp;{MVt^WGC{@jdj5!aWUb$Yal==2|~h zs|~BdYUkK2Uwf<+Ih*SZPkocU2zk`kLWHT-pF1zN1ht$ zBX{Ylkw19~5;w4)Qbbwhtjt1Y>pSH3DwSS@YjvUe`Z~oeI z<_O!-F-ZS#nL+(1_CA+&mhh8EQS@f!uZUgsf$R^czkkT1_|xLs8XOovoDOPKKC6+- z6jY=09oF7IVty!Yu#ZJPQA3bK?D3I!_UvweMNx+v$?-S@x8zz@>ze5t?*`>!$Qzbo zPNsx*9)oz`WyW`XuJ=sBs}dz>o^BxbhGXh?HpO~Oc=MWY&R+Klg2Spy zo4?7rGca-Wszb9f!;3DOjVNLaZ|8YUGL_FQbzqv=i`;o(D6Z(GV&Bp+$O{Sf?>#>}I=9yt9T^%!ra=t<~h$?>e4 zgBLQ~DPPJlH`*twMVRVq!{Tsw7j)k0M(2&Al@&e|GL7C5wWp%4cEC!ujKGuJ3r8K; z@^wA^s4q*K=WPuymBY`OoT7&lmzZ2Qf@Uc&Ci?9T{@ih=BfhU-uRCrY){pb@T_iE)tEI=# zOX~ZogqH3OFS$4PT=&;#`4d%;iheTW&82fBPG4haRaFaSeEz5?8NTpd8qzgt;`h#! z=fTdSMFD(Uhkh;c3Y4hmI@ncZi}wAafco$vIQ*6Px5s;noKM=LUnL{ZzO>}p?G$!x zY4=9EpBvCDFr@{|(2}LgUUJ~xmH0eF&nll?i28;hV&OEQnNg{V&TZxfW#|~U zF&_1~##DaHh$|P8@X+=7 zyr5RWXn zSejs!ceAE@nMlq4nqI5#jmqA=)$x3i=Dhx<;v08N{j9BW5nE}Pt==A`#hkk5vdt5o zM~)#dwZ|Hd!pZrAY3Rr@`(y5M8g9OQsX2fr{3`(QyXl1ziv|kks}R~5?9<~#c>f29 z8!O-Ql(nT7`5!<XYN@AI7%*=#Z%@|e2tq?-7 z2!&VjzJuS_dT6uRzUc0jAqkhQv=}oUQ{Cs98h~M!l1p-&_#>}+oe{2HTtZwf!{1Ja zzB#$q$fK+sCNAd{;JY$&`j&x6tC-trUHcAtUhPVq2P@mo&|OXTtxuDplPJ;kxbTyF zvzQt@QIQ#9O(Ex&bY&tnRu_NylSFY7f{iaR`grw}x+7JSJT6=P+%|r3&Hh^(>YAMz zUn;6y`HdR7kM~G1*{4b2NBID&OG$FN@H`ot`4f)2$UOM;T5!ehwBTc|UQsE(UR~pMx6`?clQ-lKvlS2)*C8B$7sGdS$s)&GF zG{v_?3CBTYFe8vJO?xK|Yh|s&H;vieg0f!p<59}md}iJ&uo5DKyZG+QiVrBt(Vom@ z`=EAqJ`K#DMk>q9yEum}>#pZgWaVh4(+`B^PLdqqsJT*IQD}SDpc{`lavnX*m0*0C zW?VK_G)0TUiHP$Y?SHLv;apO58GbOxR(|i%`=Cbltg|+{@7pkK?;T0CZl*wXh2PTH zO;?w4H-l$EkH{N3RR`>%$B_br$(vGClobe=Xo7{tt z4BOFwq0c@9>P8C}0`R%ZZQ_jCU4zzg#=vhQvvWyp=!3tj)9x!3VlJFA)AAH}=4T9U z?!~f#4C}v&+wcD}=WT4HQmO=Cpf~~l=91L3BW~)n=CEUE zs{8kQ-whnl?PiBgX0i7@$V_ptUNbB?#ncs z07tJLEbNkdR~Db1zPTx_xYk#woVIi^m~#yjs(Pf|z)hMX3zyh&&zFcIDM^AYZm)4i zaFnBPUXi^|iL!M{sC<}QZcKcfB`D8UjGf5G9u|}&T)J$yS6f5&nE8gXSmjutTw_<; zqXlulTiiK3ir;JhA(32ac;0lrB!amb#T2%8pj=XT@Y0xjhKGfP$kxAEzVgHMm4@LW zRq2j&1iIN*v|`Cd_&0h|nNMGY%W$-wx<}F4Fw$Kn+q&ZJLc*F#V5?OT-9jcyMeJgT zJ(p7K{g2LlF(qjG{$gEydGs7VHFMD?_`+J!Lgc8qxI8yPY4@JUayBxWgzfz@o4%TH zL(%;_3YU8u470N3)#w_%JN9J={ccEk6JZLI&RMSJXv#k0hNKZ%pM^@8HTS?P>%C7R~eDOdjT`z}NGusYDCl#^DHj1U7evlvs1Zvu_sh!B4yM z+l5*4u*{G9+83)}bAbZBXkLdcIGKe<);v3&`Cm9rI%O+&-!xn+B$p^~G;sGnmBx7z z8HOV8H1L4X2IGsrwsS*TFbb8~w)ALkDT<|gGB-v)WhSxxJR$!c?8KRKq1Ys0U+Y`OzJZ8Vl-e;R3Gn+Vi`Dly9Ghju3K96x$r@yjJxURZf-29(^^q z_OsK(iJz1++gP`Cj&Cn6&g!12P(w?$=uykCW>-2QQ#-wPTGEytLWCaM;4_2g5fPDn z{30snSNd?2_SfEymoM9h%AW(ScC+st?>zJiiFuycHAfxeB5Ug;b90wsteO@*9K&{X zcNJDCI&W6XG22q?TC&^e?73%gvTx!&izZFw)MJMJG?2!hU~k$}n8U3}lr@6%H=Rw$ zaH03KAi1o$&pXyn`cro(iV!c!f3+D7_^lM_%)0I-dtIx0LuLjawH&o7SN?t>Vp{WD z=Sw-xu-27msXM~ySwukuGnFf`a`kW4tz8H5jT5)}n;!qRhZ2uBB(Pyl^taOKLRpErQ5ML_`+#fke9P%RUYTi^?z;vvm`Pre%W^@pG@?IdKSx%W-Qs`8&WmV zo9Crhxe#U-q4SGLBa3vL>Y}h zJdF_barV{-LB&#Fv=Ck~?C+ypQ(qmrr!yKNH$RN7Zu6{+I+!q|xszZtZoaCeXo#u- z!Qtg;#ZO6jL#wnSqT9Qx{m?(}jfxYwOxdzFB#2Ibr}YZq)u`>>PhG6@q;FF#oU~vz z%w1H){#Y_gG*R_u(#VHi<8f0VjwSy%PR}#8Bg z2(O`fTuZHaqH{P4ZjoUZ?d2}p0ps15%IzQY+Y$K(*gBJ~NgSssWnK_9+8vYC*C=$6 zHKNMreYn3@#Liw*m!h=1O_hkqNZ5dKAF1HZlu>@%wpOe5a8);-JgYBPc9zk8t_HX; znjH1I$JE|Tib>42D#p!2W0{Bhu(7W$2)qb9eN3$sJE^{^kv_L)FS8ZW^j=1xkqdfY z>)O&O(2SlVC2Iw(&03yXBd78a3jVHK<9gqREH%gXC(oSv z+!&8WORkzPyO|p-W7M~DgM{!;uEO#pb22P~h61HUg7c)7^(XG^Eab3W%fv>_|2#JP z5_dw2JiRh_cupksQr#R=sKrHX4aZOwijB$^x5mVyrY@80?A5s^Y?l zZB9+r?E4A%e*_>MbdsK}vX9kuk4aqdYk8X+A3f#!SI^mfAts(m^?KsvKi{=_ARig0 z-WR?8^l!zn5f2&N)r;Dc;GYXsy%H1GvJz1ImHpQvQzMI_JzPA4ev|n}by*|=*Qr{P z{+arhb_8UW`+ieQ)V#zQu*g0@EMhIfWYB89+%EQKF@Q+xaOC3mI33}{PFy#D7#+xNi?2=zso{W}Bf$PElydohzc z4L9Mmqqxas=5UETwX*w^`KN<%38PYfU49LHG+#4>fI)U{tVrK$uoVW&G#SjG$FP-C zKOt{BtlB7C+?gILL=>uO=Df2l&DExyo*WS$v3oV`+)3bVEYKnK`n8yf3W=Vc9&T%~ zVYhsiG->UA7jxy|kknv>^(+MWoA2MkaIvHh@=OA^v3#b)-3GF-p`oEd%Sql`?S`3W z{G8tf$WK=%mrfmy-{My0l5Ud^+zT_0hZaMte_R@!xqSMJ}J?Y}D6(_x5eDb`2NC z&v)Okc`YXl%8h;a7JvR^RQq;6tJY39Hbf9FzX6kee9C{9Zr^r;%khg27&8Jdwyb#^Nz&9a&M9I zj+XuYPVIs0`vNTr=ULB+Gj-5s{+Juge54u^uGn3^Mt#e%v4^CjYnwBjM72Y0h~34) zzRHuOHGYrHXOxr^55ml2TGqJVoI0)%c|i0@>$NK%^iPl9#S2R@RJ*d;9Av4y6Bkxx zY&ti!6sK*K_yUKRE!1q}SHfI4l#13GLqaC;S?BJ3qn>!(YWrAb<$FBlqpcs5HT_?O z5E)k1H85M%Z1L6}Pncg@ z{bAO14^L_@S&4F|KB;|pn_(ICYs_iOay2IN1iZA%(Q%Zm`24NL zJ<;m6Qv%JYuJ9{_MSEGyXKNn?w-UBaSl%hpYtfn-%ZW)yr>h}|_^w`I1x}BDP*^OB zs@|iXYNsu;M?=MlT!f2s3=H~+_ON(v<8X09b4ms+U1l{f@ZR{^(06)z8CYm(9{X>m zTo7T5+Vv2Af<8iJ4XCoV=g6kh`tPR%Pey+#-Z|QU^ND9tNJ}U44<<{;j+9%fmzs@q zC7WciH(cT?X3O%hx`vVQIXM*>P-={ReQ`&_rU~6>vSP*!M<$7v$J4W*;o6N{(4m9n zB&Pm+ojK~x#l`XZ2o88?$L)omluq<1i!>R3`3k{Vr>to>%npYVy+rSE zoZn<&_xjp!cCX;1_gJBBRv(0j?$4r#rtX6{*sKyAi$9!k-$`IgOnns0A7V5txU`4J z2+LCA9Q-_1e?oFhF6fWKsbEAg{53QC0U=?~b9DVeix!b*IqJw#@KlO&!cBy2Z`xj; zVVvft07|zGX+70)3suPZYG&nXMu>EXp^{?OM+h&OY!dHX2D#Lib#6z}NbO1x4D5P* z^-F$TsWcJKzVT>=@U&YPf8Yo@$H3{n&y`HoEuH)owE5$l{@_nrtMAXxwA>u^+6A4CE}|KFPMBkl-t>TdY3gerb6)2 za<-m=fL^-MzF*il!%c`n)N88t3Y_ZD!4UR(lPQm_ZXK8X#m-Z30K)E^ILolt?tUyX zhO3W8IcAllR0^x>-kc)va47_zP1m2l__N-OKb9}l5hp;ax)v$#Ued>ZG{O=>IEtI7 zpzvUH=ZY~$VSO{_Rb6nUyBOI4+4W5pTUoVLdwM$I;+BX>8}GdI1lRLBz&)oU?c+@>0BE|3Z_IofT(%M^p6(5tP?$(NhhH9so2M1i8Ra0>iAw;h<#JtItp& zxajGeZ#)pCbnzgEkbR&;zDcscFpoC|H!hN@#AljUTwTp*Q5N%d*7(as z_8Fw~attt@mdZ+ggdqcl0?X`?bfgZ6x1s9KmrWC}G_0M*9c&f>L8|PFD0k!>wWvS@jrcuQRc7Y)Cc^ z>*UUJRf;60Qf^FCSt2Rl5elDG+ALMu%gB?6!`yJTCNWcH3knm$%Pi*+mr^1i)8My? z>{Q=fOBB^dZKr_{owUwwh1%BM4X~eu9qmY$Epq-?u-_YF{ep}Qv)ZE`>se*CRmX6) zkg=1)rFV(M^&^oV51J+vz{wVUnhE2rEa&H>aq3MIe}pQhZOB2gz*&-%aivyam13Vv zwL#nwn@46<+0^r^Wjo1Y`rvmP4=sW91=njt$=$8R^Hgz$emvOBIIM#$1^1cdq!^{X z#1Y)?&kE*3ptC`Yz>|v-F3;7TS^rf<7FYVq^do;g|1n$7`r`_nBiYL$qX?{IY?TrV zt^xhH-uAM$h=ShH%349gI>HUd>5u3*()vW&m#kZI3)bdNLPrm&Yy%15hCGH$9VIxr zA$aQ3V_Oma_8O$HPEKkao%ZxzVa~Tp-uynq8z1 z(*vD$dF=EDrtG0!g^epSH}gikD1-g{9h;TDly>;+qNVon$3_&k;_=iK*a&ymi)=v( zKqVFU`MSnwtLF)0{ZJdRwnh8Sv?E;8NJ)m0>SRf!O6Oagw%2%Qiarjly0nnv`l2)E z%<&Q$Px6BpSWEf^=xA+lZEwr!IxbsWN>p=^J9~3YzD62P`c;j(PHHm#CPZGCh2KNi zuf3Lb6#KNBT$+b%a(*oZ>&+R4?ftH#+Fi6v*=zQjEt*LT^`GY2YK;}{i%_VrvpuXY z6r^;&aK~L8!kpr(A#fM6bMnA&a?%*8b~Nt+g`j8f^T^`PX)~|VFalB&`R&`2;k=06 zFXV{!PX4iA7^i#klpit*Du(RuuhI7C{OU}o+8ADcr8zLmkOFY_6pS~!R(HP9T9E6R zQyCW<>nkK4d37i%DwMy6q?S?!*Xtp?4i;Dv!4#9!w)4EraI12GTr`neOuODkNH|KK zigI5EOf;&WDfz0Zn_qcYPugh4euQjy&IWwivrVJ*NZ95uh=$(`!N>UR@Ry_~5 z?4%Rx9#v?JOhBj#oR;wET^3sgZ)WU}3Op~F^S7sveA%tPFrz>yl?Qww&Kk0N{jdl3 z6Q=0|#6#Zo;m=7Yc(hZ&*tj^175UPNR!ogDl0Vpw{1IZHZon*zBZbYL2}#ize_h;B z6>7A1oTy%5%<9)PrgW&+g^jPwjT9LTTBz0JlKK({vnAdvL5$oZPqdkGJn8<4$~4ya zG>B`(8o>{>N=N^pfRW%ZJzVsEtF`pce_(#}`B+Px&Ls6`MFO(A;8uj zsne<1F@JQu`x9mWx8(n~heyWSUxyb&z_r}(rU*Jd?~Y})-N>t;5fB)E@7eO{?&@eB z*)OHM;E6JGM5_C?`19uQD1`yLp zaD4joDakXF`+!;*u8&n%Yg^3LPbaL@dtPuDblg{L06*6SptsMFSt(Zxu+v^I%Zbva ze$ksvjcmSu=B`+ZdQO~@`5HWt&Sz8Ht*VxYjIT)i*tF}( z&Efg401l9*h>zbXgKLG*yb7KJV`!~*+~5F=t7LoN>x*vXZQt zXX@Nj4A;Z{*-)GJG2ceQ(w{Ohb=9)fpXw3xa2BEGg1IzuP2e(=W~M?F7vhX`JDm?u zNEbuaa2huZ3=M4!$-kNzRpN&39{#Im=PgIqG4T)fI| zX&11Jq#_60eG<pB%-r7RO$;eKL8u*=EeAfo{zdh5jS;ZGC*3djAo&~yiQ&#DiJ z{KyZ57BrVlSpnT@GgR*eAo7dfoGBk)V%w?zRg_LZ7iqG_EzGZn+Tps+9= zcBi(|;pnG|J(WVTmoIB`uV0MRYkAiR%`Zm#Yi{z+Bp3!mh_pwO^-xJRj_DO z4ulFDq~fAgg|mA6)yP1NDpsUc_pJq(Wxkue;Td9!-?Y=8SSx->e@UgmIMo%ydD=0K z)E*{gx!jY0iG#zf$pU0FFK$$N;|qxWGOk28`5KG)TqBfTMZdArXZPlM=cY$cHn*Aj zbBUFmQExCIv*3wtJs|TzrlgDfVtrGl6;nl0Pf;PV$IZ3@cON}#1osX7{rfiyRhrX3 zbv2R@$|34(rtfH)ys}a*;KnWT{42mbYn0xRnasIe|45C6Xy9g}qv!n|+9cx>UsiIs zZnf&aqjNVhV&XI22g5V}R2#c!vGP73;f7C9ddCs0X9)iNHGIrcAGLiH)?b%@He1lJ z{NzESz})*#`p>x*!vT$=^v8bGKaJu!XcUiIl?VU1Jqjym6ayJua{n|6Omq~Hn&tK| zGTVh#ETB{{`UQN?_@`GbT0rsX-cpN*P>$p%dR=T)_)uzz!4`jp z7>V_Vas55AeW+ME;)hT9;-Ge(%h{abj~9P0rCqLAqc4Q=CrTZ;d;JH_zaEMD4wj8< zlvuXU9bnbknMW!YXbIoaPX3$AgT1xvv_v>K=ctzX|IR&{4E5y4TRw=WJ?Lv0%~S8i zO@_)+d0%qYpDy5dfCs)2Fo#p~RAA)ZkcyN3y`oj`ZohmhXT)i_{S?QRm@`;OP?*t3 zjg9>T!lwlcT~#4D|G9h}oG8dCn!}R{oEEgcfRd$BaKuhGCc8Icv11j-xnx6Un4cCf2rCgPHmdVK^0Q3=Gq}VteO~#AAcfw>-yE+-!MQ#?Roo8P~(aSUjP=%8V;NL2* zacr9Mpm-i`PftRmQ-hG--&|iQ0OqV{6+tO{D?A&I_L%p?bDF^ODIW2d`8|H|i5lRE z0#A6Zs{V22ivq1W8!)wGFN9o$v}!a`@5rA0dh*9HgI=;Vl5&mbaAYc{8xI^VQ|!`{ z)X?>m$zw1#T%Us!@&@a0VteCv-Ih-(WoCrf4;g(xyGR8RsjSEV!mo6wFS_OAk*Qjgp94&%AbnaiN&PPtN_+PGXv5P zM_w=hHh9{mJ%XG?L25oPUHK-wxa8KgPffcO7S5@(76k_oPc zaF%q!N3eMwWXq;JPvW(d_OhI7tp4S`ks^ZoC03xF_``^bR431JJYS5y`jUEG;aw92M2jI zBh9))tv}DYfMz;KCoek}WzXw}s%{>Q+mestFLE;KZ)gC$Vi%y2c~ExSb5%>EePFF( z0n}-p$E2U`k{PKX;w2&|!`4S~5I}e~5=N!K@bc&<`T=T&K9Ey?y!#$J9K5mFdV<^D z6~}IUtZVZd$fU!?FbB}m5nC0ryyE!t36&}Cl(>}RdLsa{mE2V?yoDl#j{5*D@lDpm z>aXbY9!G9htxygJ!-&;~0ctc=TZkvIU{x({UF@`q#2wpwX7-!$ne_}r^XgVBH+Jp} zrx5zcYGZ+XRL-u>jz6f#D*ZuhrM}HzwLoKq50aogCvC z&`;K7?`I3Qz}h$JPu;?$aoQZyRcinMpbzWb@#eUGHT{J63sA{=od6-_x-m3Y2YQda zuy1P=gPfo*K}OXb^37!vcKvIM#}3n`Ygd z)WQp*V2I)qW|hKpEEUZgBOIz5Ss9r&?tX~A8iQ*xZpZ1YpC1~c>3yyW=SuxyVMN}fZ^!VbvT-+TX^J) z`7o1EyD!N)Ilt?M^Qg{I;5Lhhso#>6k+mMWA7&YDImraRq& zz&x6PylWD!+F7Ze8J^8Qn>4IkX=z}PNipabx^0i=7>of(enPWqr z_U-&l33IuZCH5<_!!%u&D4w;cxTVs6ZavozK2Qqpii4$dA<>#}K1PCqG3cF}?${b| zh?2GwFOzPTo-pD;c6}0b{KThfT@QK$odU@DtjGa4!z+&#zT9mwdXDdO;DBeQ;Y(I; ze81I)_36`2i;enJZ~Fy&*}i70*yQv@Ko+<)#RZT<+^-?XPL#>G{)o}Bu+L}QVumSO zKEFM+;rr9GHOm`6!}DEjacNMwWILLdfIAd^reRQ;)^Jg5&Uk?aD#!-?0HO%o6VHpP zAY0!?RQBp>$5@`Ic)(aJ4cQapko13j*q=2{2f%o3;Y+9pY7^$=$C)p%{KVu%zdMH6 zaw2DFw~RW$!@pZVA{;Tr{}W3+nx8Ff8ec#wEUIjb+R0`fTekpFeye{(#kID#Cl-0< zH(|~y=c+tlxd4)Q%Pj^6h(ED0PyXxkzVoVu$qR0uOF)aH2Rg?E$Ish1-ICXaMcCki z)uZg0C;61A;St^Wb;oKw3EZ&I1pPwe2s#J$ZXWiUKCn=HG9t=0r@QkmYv1F5NkL5F z?v79B9S&z>$V3ePC9l11tnj(8cAa%UooSxU{!$@ex7Y#E9=C0OEkX~S#@cFCCBK75 z849@C*@WiC3&zIu$f(X;PTaq7pV%>GA@V2TySExmiI}-ac=@Qrfu|+OVJxIC*>&(0 z@ptpigAY&h@amDM>KYTI1h8<`aRiPdBEDj_r})iLg}wd5I*JtAeu&w=vy*~XljZ^t%q*IJA#@WRP@m%CzzJJr|E; z=tgC2tpmOT%byJz+ymut2JC+=j`uPDxc1Qd zSO9Q7s0{|0g+C$ceO#zdUw#$v;B~ScBb$3`!6#eiNg>q4VJlsb~KH&{@1Gb;PKlCQ`(3+{i3&mmT ze`cQA9E_lNIjinTBg}bOO1N=p_8kGxWa39 zC#BXNeiqeYGyo`{cEvCU-1cP9V4eE%PeCKi^tw9#p;APHagRLE_YPj7BN?C7%kg5v zz5Q{ofZ z5K`oEw(r0#R84tD^yBd?;QB8BbdgR`FSjt=FM_)=F>q5(9B)dO*>zkt&?R(Ar$Gn2 zF=SIAK~27Qk~Wmi_Ll|$6i5an^A=z_ZB6)JUtJ`b5Bp&eL?$PP<`mRF0%{5`Jc?4- zO=n{?Z`p0Z)Sd0b>1yx{@9GRLFd#5sOl_YAZT#fovqKLI*bahU(XLPc$TI;1cDX)V z>Gj_R)ecaNsH#TKt0TAzz#N>G6VKlNdXMEiWqapVRq+6*EGzxC*KB#+Tsdz}*TB)N zlr?P80VFp5m=B~YeIVu-sb5^)YB5Hd4i3+N`()L%SSf^&aA^%Z>ms|Qw-4Dg#z;%Y zFD7nG@F)Zgx?F*C-E+L@))I0IbdH`^iJfKSp1inkvc6cR{7fk=0*3@jPQ5!QNtIwe z4(`-jW(559tQAaauD)ae0*(Hn8EM>owuVc)S}-}7czCdm&$PBD)6Pj7Y1vz@nZxiS zhCBCvVBhZc=k)h?so8mWcnt1DCE;8Hv?QX*1B5b;I`TQz2hQExNQ;f-UfV)cm_&sZC&1fMyJ zI(r$X-@VS7Olsgjigloa!~V03-h9OY7#=^A@)AqF_wvL6b%`I9myKPs`WZlEg+TGJ zcaF}pR8Uap^Tc_`h~yMigvxa?N`2jHm2g~T*Pmus*o}KoQDNI3;$4Ei3*@qA#Ck%v z;tyK(@p1l=feii4_L5nuH=)BKxT_UmB}iMy?0gaT#h3@|kAy=9i4wTQ_WEBsk0x4m ztbiaCFXCAZB%kyMcoYC<_I38NGhk6F5`X^3?NM$EjQp1y&NOU7rg$O_p&xd=;riPy z;wA9CJ`m`6m2I^}H( zEV=%g6c93L5E-6zPa2uKO+(r#JNNjgdt&Ac;MT z4AMYPZ3F3xh`VIG@q2e8gpWxCowq|zPhHZuYE`UeYR5O6$l)9SY*KOi?;6WqN54=SXJyW%wntL&M0U`wjI~6%vj^=0~+pxHSY9&G1(hji^=ld z(wU+QQRC6giLxBmq8UKLh*RCxpWZ6iR35uf(uh8#8lYVyktJFDEQ!kA^3?RUs}5Vw z_HH=GUFDv;COx%&JYD4;kW$lu_`(ZhyMz_nuw98GV0T2QlB|17f^y+XR^qjr(84k67PIi^l6_>4j=l^Jw#Voh8 zUh<3y$Xif?TNQndOHuZJ+Nv0efGjl|8(X>~wo4>TwdgPV2b}fSjiOMH#JH&Vnx>9^ z`2gE1HmCPbL~#2n|JQ5}lxs|M>pOOvW1JwYfPUv5dE;#qCJU(Pw}~c&GP4gLZ|6R# z`4`IjZ%_eZH!lLZ~Iv9PeR%+RqPav;xwU7+y&E#WhZvHSD$ zW;%zqGo`l`>`y!-2?Y=pcbAA=EA&Ocz4_hw7L_`CbnNJ0@xcXS^{sG9kzhZ|PLuaV zSRgECv)n_P>^$R&eF#ZqWBpssdNQX;y((h_nj&hA>GoI^>IS~@*Bu^Zz1L|;1KBMf zmL2uezOD{8@QpsnZQK^F=_#LrDNmFbRMT*MN2} zo(BhqS4Lp-9$BEnxM5tvr3i@Yh#AD?9N1Ji-UumEB{Ti^B5ErN(3A*Ly|2&i!=Ja^ z;Vg?3i_fkcCUSyw6MEH(|bhGV@QFx~&M1Yc^ zKU?oPS3ff(#a@So@wPXK4+c8E*>%oC52)MG`mLxe37V6%?yToY3f6fdujQl5<{N#i zO`4wSeMeA#Z{m}j!07>vR19mk{joJobrux$P6lw#p-j)uZlPX>GK%&8%0(!d5I;9{!Eu&lqGivRY<*zKn z^z>*dttEb1R|^LH?<@e=BJqH~sCoj_k`zlSyIHIcyN64{fds@h$-#_QgY};7x0s~Q zVl)3!rbHN5o&s)dmRwqD{^TOSf4#G;YNZ?(y+FUZoCXoh13vZp=D=?QYn=J|GmXi} zFG8cfP#A16 zXU1t-B9sLAnt$%B3S>!p{X`E}ipGAb6zOG&G~8U**d99cRkChO1K-KM<*P*4BN73- zZwdSzv!&*6HVyZ!vi3;Bq3(L|CWuQY%LO3KVr6C{@^x;G-X){|y@hUxw8 zaNvHjPVemtUV%VDydkjlUI9T!Iw9;4PcxqAWu%q*)#KZm*MNn_(}9pq^!VONucN%6 zL@p!Zm-#fnwx{;=dbZ)rOK!o*e3H9ReT++x6m(!7aU?*1Qf%Ow&IxltJGUx}7mM@S zP}`-?3Kxb|evs(;nQt2M9peK7u?}0GWb#kq6a>CRPNZcw^&nx_vkx+)@%dkGg%hj= zkbeAl+bhwi^MjD@cW+JC@V$*@M8+^5&XVEYQC$X3)Mu-U&}$NiOQGt~t*Lagk8%!B zV|>F}z^!NI5GVB36CVKj zub6g95+KjlN9uslS&kJpY3P%5>|s1=PrRg`1SpeV9mUH~{M^xM)Pu^5jIbEF4dtCsrG1FH%keM z%z-mN!9BC2bU8vlTdGS;%gfkI?marVqKnhebE*Q*(>tqlf2}Z8bhWU$N-(#vgQY|* zlpH`ij-9;pF^iq#LfoGH0i#_E^;QdAQ`l64tC6{>> zGh9YWQt_^;c{*$5_E)~wQvpX6^mDfPdgJx$yi{h_ZF;~tiG{CFE?_};TcLMtKaNTBn(V~=86Fuk;kkbzTi)FHV&8tthCFjZKS>RU1SU zt(gym zqDzwTT%2Vc7d|LNvJvjNq~9V!nU`WL#yBr}}` zc3VUyL@J$e1aS2IuWfMuy5P zw2z#6qw-v&Yt?%e&GD(+wc+;dhE55|7N3GxeUAkkZ=}avE3e@*-dhu8%Tv3C=&42o zC-#Wzgv02x*jrDuV-01q?f^)nNjtXX3q{1J4Zhce6 z4-o_<9D5h1poDNtUu+Q50z#Puf@{gr>{ZHdC!{YN;H!ydaO5MCiqSdiErN zK89n%(BHv$QaSge>1vTVUDR~ha3AanMc=v2fbTWN zqguv2$y1=dSkU|EinUwCZt`~QS>d{j#Y7;ob7P+!kc(kRNwbt^2!btxGOq-16)r@ghkz}3^`8=tJ#q88v-O~3 z&uP2!-VXt2n7P?>HBT?N{RhrwePYSdD zmnxv zVO*?!P6FZLbeVeVOC;p&(%(B_NG7q96^DQqo=0oeCx(-67K5(jd|)jWp8T zNZ)6Bj_1>F?!7a2=KgW-%y-U==lH(xzH9Hj_S(<$s};_qT(pLAC}$zPWBs&YNOmZn z3yj1SK#^#8^PtH3V z!%-FIe81aM$_} z2LIN@Euc9RwAk{!ee06haJTqDjO#T4VUj1Uous-mdfziMwR0Qd-<>5}`&^$=uX^?= z{Vno)!<62w+F}ji=7G_sFFa#WDl#9cLJBWTA1vX z?G_?8zva!&bSC*p{%6z_dw=PQ2N)ErH@cdiSI+-lXq6dzcs}M1M~Tyh=a!43nB$5v zFKOb>wfk4UN+FLjL_Gask-}Q2)MZ4#O>}=jd8_qa-?M+=ZkW#3JmW#MVtql54bp>t zI{?VILA-PRTbYS}_N|+*KpyF0^}#m$w^Isu+X-Tw3;C z9?Sbe6cYs|w{P8=#=S?H^v5>?tV$gpT5-+cvHTyt7Wl0v1n?ya_g1K&8vpH@Qea?F zH??|FJ^XK-6d?9!j!!~*-2NCVGiwD>p6=-N4O+Z zQ7;22#Xo4*zovft@ny+qk<@>#+TTNjpg8e>Fc5{@=NC+{)&m= zB9pMcwikQTyw@$+?jCSjsQd@X`MX9NrPDenm(rdFbQfwBLBiVicKz{fN|H%)X z>f+8fB%oJsxPlmArhPdKIO{p3GF>Wp5Zw_|Mw+qst}Oz=CNz#v7GQQs#pEL zhZb=ChPfTq;}^OY=wkpqnV`FUyJ1+r!*&_HW#!&UXWSRUhv?T`NO_%lAr;`Vog3V3CS-qlZO0pU)lL$u(`tR(+H`pndn7$f_$2!|f zN-bIekddHLWK6AEoLPFf2dFN$^ecGha1DdZ;SAvWc_^*jh`@hqqCHM34@@6fh8;wN*`Q}?vO+CeoI4{AEi0a5Ou zY>Vn+_Qn3JHvs)aC{(#Tb=^?_n?TL9Xe%~j1s;L{u{@2`uK z=FbtZa5(_`)2?q(wV(WKxj!pvABdyTPm?|*5>-cSUCtn3?%-j`w=|FcTOAxAMFH?B z5KJ87Jx3ZdMg6wQXw_l+t{Nb(o5*T@{_fJ1Hh%De!XXYw#Gdn8(H(d?_7^Y^r9*y# ztfbC6i+Y=tN1Lr1Lk4kIF;3<+b6W*s4ohz_;`7uC~6=Zz>uG6a&B_hLjbrIX{ds7Xpthcc zOSICC7UD_H7+|N(YgqSXqAiS(G5s2Ob4@J$yNWZNQ5?8$2?;6j#ivx^RWUZf%V8sJ2Gr83I$F zR-fl`%q;%?_9}~nM{9XQCii9c0Ly(u?N4G+@%2e@#tZ9&v7gW8ntLb}ZchQe>zDxy zEw}V+(>6eF5o>0==Igx3!5aPe3e%`cR@G#{g z<#(GFBf1*#hiW!=T4K`-z3v>MOi1V1DdC;e7{8&?J6YeT67|jLam&#H`F4YA6$R$#K_Sej}1{RvpOp zxw_Ihv+QF;Rb>#+SRR+123T(g|MAB0bddBqDE7m-3rs7EF8kN-n5VmH3`WjHf(yd< z#I!Fx#5(V|;(^`iRW{>bqqLciJlU`I3!>;%nNuVpv{g33ub?t3>k>&xH}l;dW1Ef9 zADCX9H=d+nr2nax^(;U+I+=U-6_GBI5gd`h*{h@)Eb!*lX0~=MQQt53$g+Lvwol2~ z<~49m!#dnSecHCowpf4c=({EA-{(<*B2|#AF<=9`8qPB(+1xj?8#qRfm{%OM`ZMlg zeS7DW8Zt77>a+WU#a-&WdlyUI5_+qSN4+BP?cKw@&}BlQ;&Y9b&R18dKNkZwM7qG`N%XlODmVASx=+_ zrno}e-8%d44@^5<+?{F7Gh0S)-fVnFV$krA*+CDlRcG=OHaAoFG}9-H@nweA>2EW= zeCEX`&)!m$=Q6vaPa{ZlmQ!0?m1&V49n~8C*5}U9x>uK}rl8rkLqEy(+htE^2%@CFz=^;+5)`qj=#@)cKXlt*&(I#g=b%<-`lyUKNvTrS_( z@}bQsY4jsy;rJ0A&R9NMZa23b>fisfp~OWIBn@g5pa*Y5kyx+DyI$d!be9f0={iuY z9!_bu)A=!)sGG40wrktA^F{o%`Qt^WBF`A*^d|Fx{pFTZk{7NY~=H1 zlB!<&_H8znrre1+_q)3An5=GYGm~~jfL<_>YHIk8r+%H*F{#g6R|s#TYoGrxm=)ld zU-bGcb~)JzEWNYZE!-*Dms39tbnaLbU$eS)uDs0B-EL2Juj_3f@qWso$pnn zQk*QEB~`v{7o(*lX{Ti?$s@gNSEn;M;b_-t1pa!*BcGKoD??c!we*mJnCDDK<)oEC z(>V7v@D=~va8nUKIFW+r9>6u+8#3l_J94n@aG2Zo<6h-7aQRR`QTccKkOQr@gHGqk zi7S|hqK6AGFq}Kromv$6G~|Y|;$97J&BiU+mpcnyV`-0n?@89^Hq3EVXmQ%?0OdirbP^#X5>cdk++9{t%y9;)FcV<(WDw$;BLJ>eW{R}E;)4muxx#evCC z(}UTl`&N&_i)J~EiXTi}6N6>2Ms;1q9NL+2U;^17#anup^XB1Kmh;N7&QbXBevgs! zJ1tla_Npb2%-j(yzS9|lN&Tn76wY5rrPF3ncoq3e0ZDILnM1fEP*HD zZk;$OOdwK4y^8s*@yp!ZXP-%9$^BZV9a`R&Ip|L(&ipLuEfqZq)V6NlsusVe!<2(- zH}y`SxHxZ^*B2`n!s+ z-i{wV#~2DvM_Ya99drlNXR;o1ONsG2e|)-t+a*k6dr6W&L6Y*uXMuQjyt?)hc9YX@ z)=JxAWqVXT8jl85n#>)S2TsA3rMFb7J@Ckn#M*sh$mt&Cj1Si=K3(4*W`0LmiuqBt ztxLp>7cDEooTnVlI0uv-mMx!fbM!KmOUlRo-nClg3uG^4M+7mksB-W*MCU|DTM3a` z=f^GH{;gH@9AOBcA7!)V4qW^%TM0!8*aBPW4a9c-?6z-B_PdgX1(z^iL&qMUODp$B;}5P($SnHb;Qx2#|GznH?zBdT{L%vazdHYGPD|{G zEFUWzlQ+5-)&xGj!a>2L@Hm5l`Q@fS0Fgg;(hcMM6f<==l_ zfCB5RSH=Iy$5P~Em;hPFn%o-y=PzjP5H!s(5=^r-U0wimz51ZVY8Hx@(i)JynpN)f zzp1!}_3zgz5_y8-Wo}1)3*^_AURA_WL|pd}*uR)6pBA{l;??rNW6Spm~Fy(K-d#`OuN)`Wk@1+o&gA2AT58_d<@un3f zqB@gq{(bHQ(lFOAVhk4s!W@p!sU|h z7ADNBcu0R2@VeVu-ELH|4j+n)dK!Y)5Y-weFeS;#A=7S{sqvZ)uhVue4#!9r-~M#a zbRG=AcCH${9p!p^7I2}a*+W#j^9-V&`EZYe`$!cqyA^O(ijxt|9mg*dWUNi$of@3m z^Kh1l9Xp4Z3^H=Sxu?IBU7iizYS&#*6b*u0(gI1(%fOItoR0+1nr+V>Jnth*h-cfm z^5bzBWKSY4{|s+=B2xFG4R-evm&IUrMKK2HwVT;5I_o*d&+T8>o^Ng~F}&I$ZP9z~ z0%uK`&4M=n@pcdr(NT50tE$9=FdcStG4|g81u=*G*nH4z3?UdAqNfQ|S_k9LHz4>d zfK|?=FB$2^ah2B`1cw#TH1BqokX;K+%BLefAYYx~GXf7Gyt2~=m)sl(z5<}wx{!Dg z$Rn$46>kK!VeVj_H#&}0?IgI}mS|;2Gi)Y2F}?|tnCXHAHlsb9scv_~T3X3-Z=r|k ziFvXPoEl+gP$aH^qp3)eW3+cBY3o)!;{?CJcmB&Aa5uKR@mS1(lhC{^^cnmq&)&H# zWfu6UgT{6jqJ1J4Stwmk@bU3K`BcLVHwc2Td17o3*RG;eOB^m00jbg5XKlOKn+NFy zgEgM#R?3#L=@?zqFkrF@c~)RJwgP40E0Hlrc?^EGWM37|0c9N=`-|ykZ2e->}51M@px4qpkz9~qA>=|-Ce7G^J>5XFw zh?;#T$B^#j0j_ipGmy;Zfnjk>AvgWn4kwI%8SJ)pmCjs>g5k7Eq{HR*7GSE2=Jpp2 zx?PH;Jogm*1ga)kMQRisvWqhZ9>I)vs3y6UF*uzQMvZ-FzW9yKF*z!{Axw7jCe2gI(W+$ayk4{UxJb+{@O}LA-8%nP_ z>-58=J2wJ^ru=hxW$2VMQEn^EZ9fuw(TpdEG2PwNb{wv}u8S-gU>`Pbr9%5ZnFnEuw zEcw&|0ZN2xVzC`*kc7)%s9NEWhduE)XqKM(X_u{WO)bhuAuoYR?0nzY)$!C-A5M|>%O>e6xH#x&KQDLGu#zEmiqPCJ>5@^RboPo z4K5Q{JWTGzP7y%Gqb@-q#`&;-p5DkxASgtuU=LowW_4?0-uV6Rks08sIxMYODeRFF z?-yA(G{JvMd;|Ow8`Fea2H>K{NDHS+US+CWO;e@1e9w`?YVaZdpQcXVg=bXYUpYXyS;o(oBkxL!~(P#jV5C1>s zTw3Ev1)U=g)$wd6WL+%HlBU)_gEhmhj+`w{AS8mZj0}Guic*s zSyDC|h`!$*)728+^1bP%e_P_6Ct0sO+;Nk}*A$xH=pc{yzf#YxPx_ME#qBS?lKVaZ ze%95+zxvEnhMrh=urWW_+BGj*xLxw0V3AgmZBWaXG;jwFPr*0++2f2yCIrT$DGG6} zLbvVDLajjk28FJHX_~J9EUoRtfhHy3@3^hR+*ZUm-0JUvBAR8H7Rz%9WeAn^x!rWr z`&IEPfBmX31TUkd#h{wC1o+M-JRcVjz zDU_U(hNc6|6 zcm;4wZ5$p`e^yj3Sa{PjazPcp#`5=o!qK44syd7B|NB5Nr{yTt_!9zFrXkEp2bt#} z328@CVC}L%o&nOMFW(A{bl{QHYRCES!Toa)tT2Pc0+i(CbwQ0#0#3zm;7l>A^+GF# zJUDw}lgvCH>>nWNHh{peVg~gx<(U?nyR)AxOojhAU}mfbWYaV?hp=*+!XuB}dRBsj zPb)m@>nEQ+i%%a0%y-*{iXE08FMZ38f$@?iPo(8+W5v9X|{!H3oeC%d~VR zR1pGioOg!|gh21G&RxVo`74 zY|eJZS;!?zA`0sb{$VLIWwpAE|c<|Rh@DAgU^WF(*5+f zWMR-$RPZ$lI&bf}PyH$;L!KC9h7eOCMMkJkj&_ZY{8+Wz&TMI{vb^$mcX;SEW3i-= zv@2PGL8p|tGn8*ZIY`i4z2DCzYxpy|VS;ojzTGtzeTmJZ9sBU!4-c`Ih6+-OAibw; z)jVzsLWD!CzZs=a`itJWWC!f{H&FRnprN7lLniyMQA*4*)J^AO7`cDqgz^$+T{&dD zQ>4LdpQ~z7S){FP*$0Pfj&_4IJ55va>|m48&CC-nH1-tBWJ;_`z0aogr(Q%}{9f`Y zwvr@l&mQFBwH7mU^$`6~OM~oe^T|*|!x8H^dzE8g4WgMD?3BY@xoqY&LEjPsrq(vs zAA3;!#0WvkfOX9M)D=Yk6J?KBeup8%X2lzq57Sod$%qkn0yAt>e6Lx(T-bOTG;7NT zHf8gZS%?5IN0hP*vO6r#kJ@p%3w~BsI-RXu5;cS#I>NV6HjcyZMSTQ z_!nbbHk*?tBcOpO0arRaB|48S+d)az51KSna5RX|?tn!|8EjM|)@)W9pk8V|SOlik zZXE5=&uZ!NOV%bi&BVrhuX^@8%eUdb1 zUN8Q0@=~9oV6C!_3cd@3NX`%HP76uwHuEy}lSl|o%(I58*?e-9&{eIK8Ic-if`2xN zMnGODdvT-pBbSKW8IUj?Pq#|*9~VYl_`qs8Awa^c`;tziF+)(rmI}G7)FvqJ(H-IY zSa`9pjE6Uk#Z9-pCfOO8T4#rsC&urw^D_*piG?8&xE6^(k zX5%LTZ8#>W-Owa568$*PA(rYKbGq)B@5fnvf(1w24r>|zkKR56o(F`Gpcf+aU9O z5SphcFFJn4$vRwq34Y#^POzv>J9Tyk(LUK>rcJYQh3+=cG3{}Cs7;P-8}xx@BxZ&0 z%Y}EEXyb>$wl2LzdN8UZF0YSiVTzHbyw&xhTdpOM(1YIntb1o~NDj&R&a-eQd_~ebm838V=Vb zikH2SEWIbq41XGrw62}DrWB`)po<$sUx+m=_GN4In5?GLz?yuly{bs%@&wUJx4byyXt-_*n%5_KS9_&$K(`d6gGIUIrs1_3H^tgZ$O;iP6 zxK1WyoS}Sq%5Gq3Aq^Cm3yhR;&KL^GRleQ07R`FSg+_85YVyq(S*3(yU#k{ZdhV*C zJtxl2pa^-66bmv;s8uHiCMENsD4g%6WO9>e@Ws+wmGs}|$TRf~fRQx)P?YL8BMl=m zIiBXPmeVdFT-!SS9hu{__xI^o4pOy8NV6}UMV%sqd%K6zf%luj>LpZXG=_-`b(tR8 zfjjvhh{a7E*Hh(Lw2GFfuiVKktKHpIPq5Y0^++51{%Ssm5wJ@-NNM{(6lmPV69F>CB8fm%v=&zQqEK(mglKR9Z&Lkfc)7 zv}Q)GDW&~3HWA4>)n2i*Nq^##w0$qJ1?%H&m14@|`JrRAgA9}Md}OIQgF+xA&_jhEa164Y(}!;Px- zsZ7c%GM3U*H&VZ&RFyI0%B`17?Of<@|Hd{y@Aoy2E{Ii1qt?kdo1XR5E2=VgHma4>L_g-^BhPM_M@vpKtQGQ=vSQz|Uug8^hsCmXN(%9Y zNGAtpT;o@JP)7-?iZ(Zd_`f;UeZJXiDME>(&I7{S(cD1OW@!ec`qWa#2p?^I?lB8F z+~^JwBXGV-a?Lv~M%UkUOj=ERts)w-NRtw+4G30Q)Q@Z}uE^>XvKpu)MtBE=gp~iT zdS{*r@RxqnU}r;5ua&Me=OeXlV=})^*te2Cj*ohB;+%`A79ekNSS|kev1p^ zW;YevEqI(SWT(g&K@Ns_+1dXrSCMonnv(QSqiz)!*oN6L5cc-{g%T-@lhkUxAaMbUpsQ5QWQwou5H5ejv38G3~QuNx7u&umId0?gMfhwmN-_% z94H5}1HXy|M0i!O4XE{?-H1@^J1^%)$mD*`mX&KqG@#k1k%+ppq`Om0tDteWt%DWk@b~v$8EAm#s02@k#d-t9|b_Ee29FW zt%#2=c=YDI%X^bXOL67d7RpvTG!v|E_!DW3DH^hs6cZ*E;s#ki1kEZH6J>FTZW)e6 zqVS?r+=hw<(Kkv0LG4AH?-U8j0ge04dsR&2XQBT0AD-GMNtdSgFA;pX*pzj$ zRst#E6e)}R!N}%Fjzl!s{7YcsYYuB_cUas9bOH*4o@O( z&xD(es(aa_Eu*&21b>aMrUlF8xOGj@L=U$mkH3!1`b^%{v#6Vl0eAVFHgm-M{`t9F zE-d_qmfhRa4?V;}F)0FsC@z`~c>kQGNH;2PTgxsIKt)hZQY=uI|cYx1-SfK1%6dqX2)qVXnIDvZ?srx7_R!2(N zL5~;(K?@L<&~y<5(LG4*3tJi$0w^7NS&`w~SyU@*yqOtxZQNfcSaSwVjIxQ2mNp+O zHQ%5`GX;HpF{tjhs#8iDh)q6uSWJC+#n1)a%uc42p78tZqpWF6R7LW$`qNo_d#_pk zp(;EL(LNaN`oX00-~fwv6q`wCJM0kPBYj2Rgf&}hhos+HrNE%0xLzkrWgv7kQ!Ip* z;RoRAB%T_DYm`_Hjy4f+n#qvsp!{lde17~2KO zwowGCysjvY>zJ8pJ-@V%r{+lY+?QB^P z*}DsssXkrRAo~vAfprA0vz^s2l4{`M3P>8AodlRL0*8?fpi3_#gcM-@C?5A?(%Wnn zVNGn+c z$RE>R@jGW2D%L;0#{LZVh(Ia+%R(w?>`X(<**}|B9lZSPA5Y=u){CT;BH4|nFipC3 zRZBSEc$KIbdE>C>0(3D9J3MJY>smpwx)0_Q0`5C)d@I8x_PlBc5s+50D6|l5@B`UE56}kI}OBqahN3euu2tC7R#y z5rvmNohG0+p3x|7)U~fWHGPFQroxl* zQKb&)?Uw%WR5_NB?dLVD-7#{E;_?)PRkgIVI%0YJUAjf7hTt?AfdjeJc>(6#Ntk=M zE98e5AqXL}fP8NFH=!hrQiK)ALj9H|N5u`n%A@yaub6ek3+A^K^{ce*+@YD@Mr8Ho zwGn_tc2(MdDNFUn`@5B~v0}81YkS*0(!&Ub0GPEky?@I;ZRq*)FghL-60Z z*r1=wENy5FLcjoLQf^lGRXCfhr|?DZ_BWH9Aqb_NEr#Fj*o7 zA13sl)M`g5b2daWnq5?LPjWwh>C~jrp4aIid#Po#0%Piom)G_LCCLbQ3{87eWzC7u zu0Xly3L66~dXel*@4Mi4QS(Bb$*x&*hK`y#7cRgMT)VO^@Aq7I%W$WFr2#xAJh&KJGS~H6@+3e|q z_|x-65`cBBMH?-hYDDq7SCL3%kg=m>ETSpgO)q^9+r^3Jc@qq#f5_0NbZU^8NuiJz zGGOCh2lopT+MpBeHSktk_5b?D$^`&uwK3X5FKmXpI0g!x=_s`jNIcd{f*6;|DT3w6 zP`Al>c^zjarL1r;zfj7QE7F%!Vt!&p(*&!Nd5dsKe0JBA8Il99ZoSi&{miNkhocZO zpUb)SrZll?CUE&IZ9i!!S@rO2JL2<{p^jf)9LO*b@^aF!4d^BT#;qK~Hn4d78KjaN z+m8>usb$4}$KEY}Hs)L%?{_C683vS@hZLvduWqa~LtP%ZAS)v?9IB+Mok(=P#PQV= z_HliT(~i9TS3|2z985jJo#f^Z`@&QNS5#K7pk0L?*Vm~QBcE_{(5jVQ-Cx=XtDqC0 zD0Pp7`1_*tHYX|9T+Y}doqqf(Oi8Ol#5$Obwze35V?&hpHOGjhH@3~=9$*yaW~s=m znyx21Iy=S2=7%Ke!~qOOG_e9ezPaHd01M*Rq=gR|~9V;lO4 zl(<-R0A+V!`8&xdlIKpJlRg_8s3N@vK$ot@N!dxrBtPT4Mm3rIhs7AVnM@OT|78v5 zm5}8$AQ!A#3Gajk^XL405(V?0eJAtvhFSVr@8y)SvNf+W5~9|l1lwj68x7{=!WpSm z*g?HbsTc2yrGM{>Pxn!v?DK@M|74QB#IKYo(N-;D?UT52e1}NmvyX=~a?v#OZ@)sD zOK~MlM?3?q+P7qxF-n%TepWG(j7NX4?F)WXq3K)t3=KouMMC9*NP6|9a6g=&-kZt3 zfnEeVSV<{&4-M-@jy2+DTaB9HeXcInsWsycZ}U21O&sk*JS;=yr?;JlfDrf?xZxF2 z7+;tK!0kBa*eZkt)c*EwecsTfd3}v8G!?Bh910{X{rcf1qlC#HJA~*vW7(Wj4)Z`qIyKL>xg+h{sYLHCAZt|MIFtAzJTa zNHq#EA$%hHj=r} z8dHm;1!Du9_JUoO;!c~-qUoG8jwrk`e0DWXj95S2L!#0_j4Mt;h|D@9@p`=2fvh8? z0`0-Y{oZM!j1B8W*5{O}-AAZ966q-tu=iZ841SWtzKT}t1Xm`VU^I&%+N{#g)b{4e} zUu@v)#|4X`O&X)8J1s^IX-SjGw2bhy0OO=g zk#Zb(*0MU*YH1Xpv|0kc&kMIfj znKa=hgSiQ2frB0W>fcJ0Wt6C{d`|QAu_{*Y2UK*-yeZ!4lzGQSuTG9J+~)x;O-*xf z{>t~c>4iF#y6bE-!#UFqkS$)`Jj|u>{fLcK=*?Thu?XqNoRko@qV%L$G<_^+G|3q| z3)7P~n-%;}IJ4S@5DW-IR_G3J>p{@w)`-<9_6~FCHU+%pjY`8X%>O~CYN~}`?5dNG z=ZJ16T{x!@knyoklr2a4SED=X9wCzQS_Nrx_XOUIQ5&s(q}3cRPbU-S9auE_*e4_) z_tsIf#@S=9CcO#+9o>3D8h0^T=mKxA`FTa{G1@Edr?$Gs4KV6xJ8=m&zfp&W*-y)g z3>9iRc@>kBur`e0-wDlsCgaXW&_>xQf08YzxhE+TXM^iDT%?7Ef8Z*0VRmAn=$!Xg zArkZqyY%I+weukoj_bs0X2`tzTm@5ameBk!;R21?u;uHeQUaA)ZfvyGIaTW>dZK8; z#+WS`J}FYn-jh1(jZ(L*#DYq(dXsRz*ELS}XY` z#z`@9DU|ZswOKu+N!}i|$C_9q=)*oS|FcO>-ILr=52?B%{HFaEyoHkA7mjbPDLwLWB3Lovl6AgMYgEd@30l zFUE(6E{o3^bXm@xu`&I{2{#*_$d*<=X2AP(SkzDAt?rWND9y3&_Snmbj~NjZLyz3E zHu+P`V2VNyTCXZqj<#a#f4NOhtefj{u{psnls3ui~WuH5+{p{O%9zVEPGY!aC!1egAm%3k?7RDSUeWw2c3}=SbLeC{3-) zU474bb`U^GJxGQtfMU5!-2^t%g2!1N>~00&mpl2S9qfOc)-#^h5Y&T!fM5s$EzOn( z^NL;etzh>hPkN1t!I(%lCF!%{5bl}@2^RfH;zSv05f>V+?Y(RN^Js;UDTU^M6q1O% z2%-s%uzhg~irI{nzq>oFB)7+!xihF67nRu-fZ=}-Qk64B{K-(Au38W={%JQDLc6iX zOad{0M&Yv`H@;`pch;>0fON;qkFSAi1$bFgzy$5O#++5RwD^aDUtJ!p;_|_l(rl$K zDTD@l2=Hx^MGpX)TUK%=^YnPr!j$H?U~lG2(zdo`kUex`7Dp>uhwtHQku#oHckXI^ zM&(#cDeQq>zzlK_%#4V{9pTUfH2#aNeX^7=KB(`!tQA75RHRoMT>+90XFTFE90`ecv52OnkQ~tIO;U`bAZU z^vi^l(ABR<2e+7-xTzwHAF;nzaDo%n9b-+Z)O~ndJZxTow0RKnJb%Ld4YGfl;t~LkrONCWq&5L**|(9-CL>YcV;vhoCe0aD<|(D6$0@M{ z?a>M&)Cno8rz89^#sq^@H{A+ahRs({D!shCrVb4p`suICroB)_wmxy5jW8Hdt48|J z!C0-`g{}l|pd0Pj?_7~eA4`DVrqsHN=*Zc3>m2CUK1Z|tK;--UV@#hEccMDi%LMSG3xeX5@Tt+y4n?DLK*O= zejf3Sc;TCD6rpzA_9)0RIkyb!!M7j|$W|t@DLT-}RA6AHi)8=q?w_{cE^U8Uc;z?+ zG*6LG*-CM*umbV9xBP#}6Ki=H&&cJb))W8)U#8N`f$rP-KUlW@1A$ z$Efxynt&MO1Nu{5`l|;Rn~zpUZqhs(&$G%`%NW)<;T?6pG||cc+EdT~SToXn>b0(n zrAbRs;8jEvn~*YJP9YzX=F@&K?YlJ!El6<(*V3m=xgZqsQEx~Ysj1|F{XSKTO(PCf zpROy&E~@kmms#9>Fi@U8unUL=f_#*Zl|j)HsUqbnMk<_&=7@Bt>?@?_*ZSDhAxfR0 zrf1yju}>WBBe@)NNT7-7=~uNdgYv+L`Ds!AVmNG+(i0Pf;)vti_gO#;38cVYFCNs! zM%YS;N+&LZcKRLBVaBrg8zw-LI7>I}!PFBqAHX9INgz{G?}07oj1UxzaO5fMaMz)_ zx;d^NWfsW$RpsqGG@O==^Vm|bUEm7rIVU}45qAn#bPk245@Tl!N}grJn0&bK;W9uQ=260=*MK0-zPOfI(80{+kj5|s z0>u%>{mIA{)woF{RACvnC5v*{LXz7g`1^ae!rQB^XQ z5bu3N_h!VIQuUV3LuMv85*pLvUX~A7qQJRMJg5~BtyJb}yenF#t?+~tx>p9nuhJ^i zS1KX!_0;wgt)RLu%7^V+<8Z;7EAIrQD`Z5{s_twqh@V{GUYk0OEQd=U7-2M4W6%!!=Fu-hHu;Qj{Zqp)E6g6|w#Sz}m2TW@$$ zr!AXCdY)1p7u?Mc_DYDY`aII!;~)aE_)P3=tl2(FE8a0siA-$mxYNulh@)mbdG+)H zNkDi-Pt~h54BSU;oc5a9v-@FG`q3$k0(;?Z9eS^-ae3I8j2hiuUGyc5`vJJ)WiEDA zEH`sOb>(_8!6o$@h6>`KDvFyBKdRo8tpa7a>5ch!R*q;}l_Pw$M5cQ@n7e_Es6t$q z1#_e}OW(RUA)MEeVEubc6rMeMnTwy?y&2nIQ9OF)jzJ)jYUQQ*d4*j5vH2;5j2LQ` zPyObgZjj{27RQ)F-AbbSj#>^K8bP8n14&Z+3+9WcQ>zy0B3&di#TaL^oh51J^{jKC z@ltOd@Dk{$3|+X0DsEm4!9}BHxL){sYBQ*3gPrNG9E5YuMO%-I3rZ{9n13dL%4^ho zwByUDq(|eJ12`aM>C=N9RKbu|7Q+R}v1$qrs~kkcz50p5@>!?1z*pWq;o7cF-73Ks zahO$@_~ljc7+qJ44C!9B|bA^a#HoT2`S=I}ld)TGK+J>xI7yGrfjvwpbk zMT6Ts2dP7%n_E1*WP&U`%0+ zTV6gKdurnxUb1&q*C1P{r*9>V#t=^mHBt3-Wy57;Ns029N>$4XEyftnaYFNtrU7KK z=)gqlEv2BiQXiLX*5fX5C06|pl*y>r)@_(R=Q_fdPNYzC6fQU&rlW1`h87#H`lKLw z1Umv_(HqRx!%G#O&X_%x*L0S4wQR%IZ~%j=fJ$p3}0vTb{gm@if9 z8gYN>z2}Fh8E=zQ)Mg~kE0Qa8^RQB0O|!qF`dHey_#=7pK)`*Rd-87O%lU7H)pJs) zc53v*oLv1iWl48fjbwxAvOj%Z33cN=IIaUAvC}Ll%BilGh1y`pYr+0fNZ8uh7J0?& z0hb73;WS4tF%{POun4D$wH<|w?8l4R{EIO`wFYsnvrboME*~`-zzXkRrJORx=p=3U zX#u3!bDJ{$Pm`H#Do&3@LK0&iLNo8ISXswKRCIgE;WW1Uq^hLkqe+*{uxUoeOc_SK z6#I%Odt9JjPtihUyhb%ZuRR)03zTjbl5XA6fO1oT@DXWgd|9izn+Zduuv@CRyn1%0 z)lN1|n%e+%lxbW9WlVsNM>=2Mx;+kgUw{qh78Y1k6FIr;mcv~P`HyYz5iIGYIOqU6 zb0j!ZtbHk(GRS!rpY%o6hK)YZ%cx+TBvZ)DSHK}udp7LVSdmStu6f0-_A*XUR{#!< zeb2R0iJ*eIS+`HaRKqFKbzysP zfBfQ+&`x2;3#5VmLWyS-kn)fbzpZznw>H_{$f6Hxv2?8Llo#rv3AWSlQbCc7(YzRL z;l^x-xGc!QoV`OM3P?vkHv@$az5TOQV||!Ov{YD0*b&ZUAN3B z%?9o>MkadN3NRb4<9j8Dtr_xyM5LF3e(in z@`bTfB58t5lndqcKI z(fO-bmBz+*Zw(!fc#H)_#?76x-@!U~A!P%EN}0(fZ_-@a7Jr?Zc(ya%ZU1doF{kRK zWsOA$6gskHgq)iHa z0vD}zn)FnYlx=forw}U0{261MeDyv-m2HLBqZtyrkJ7jB5RW;52BL_``hnG7$XP#P zRyO=r$}EW2P61mH)q!s!s;@MreYn^cL>`STyJx5^*U8JUESZx`59i-h5?+&)4)hU1 z-|8H}yHAN`o=$C3fkNo|62m&?HGPUZunV91uJsipj$^mtPa8SBs@m39QDBj{NBk`{ zmW*EDg9ZzlP;GR!c9;_)^11GhMJ(T(%G??XkTM!eA?ItSOdGd-F=Fl1xYsf##L4N5 zC&XhP$b^atjr(spT{v@wTtW1KpnSQC0>Lzma^Rbj3$wWTJZMF)7ssdr!tziWwm+T` z@+_oPr?>e)z{vJdcE-fE_paz6%|!q4*Qb$wi7L zIy!r=t=~onW8I_>2nfS?kpJhaEw2T}-0xo>e$gJoJ<#A!Zo#78mJ4p9QgzrY!wBhc zp)*whrFg;r4e*87J|V9C7x1+|-lMAXj!mtG$ZSR zt5HO4Xpn9u6(OL2NTdN15me?WVGx=0Q*kz&&)#R9wbnjE&pI1Y9hLFe z04VFcD)Ju?mpSacOF#*N5THAuvv^8;T<1{wu^X0yc~4$@gxb#Z&HXpz4$r5j{P|!h z8RFg{wnMNw?bjQqC-WFlWDB%LF@|-&>r0b4zcnv@1o*;IfL9HUv8OH6v%*rUq0Pcsz!R#-7a;3hoQ>+TcQpQ;?8X&-Vv5{%@+Nk(QDM?$o|gOS?)x;n>jB@{w9&5C*}})d+7;3^m4#|TgkQX7q97Jfv=T*t z@YuzK_zkD;v$uT)zuWRtaFBxW1UOY&h1bKVvzMhZTqCl=Uk49N09ENTXoJH+XV&g)}JS z-F^erz;Jy_1wSJLdN2ZUMf>}AMY3+)A>_ryFFlKDk-2i(9=?d9tntC>hW}7nSfm96 zT2+jidOCrHqa9l6xRURppf6)#7Exi;LnjG_V(_yKk3iQ@JQ;zxKCCptGC<&mUP*yr zN%MUUwb@3>+G%NnE|5wzX?ZDuVUj?D!S2GCniGs)1K3SaMD#)GkGlX8W7@TyEa1y= z**Jz>>&XEZ_ftNIG9>SYQ9Va~chv7e2KO!Ut~f;u=a2~T0We#o6F-p_#sO8F2ptD% zOsLyXr4q@Df=CV4lDr+xD{!d+4rXWK*C~#{lWR+%^G!)NifYCS7$C`X>%Ioa2I5KQkx2Sn)fXw@a^Q@B%H<8-FWScnmB;B=TIv>x17}9PMDr>GAIbP zyVHo`3pO$0rGE-9#zg>hc~S12UrF?XCZh(BaNV+@d%h1St^S-*WG%bhKkSmiQ<-NY zRo9x#h1GY6;MFKsZsa&b4`|zsMDCQgBphi2KzM?v5#-Q(16M0J;DS9u)TnK#(|MFD zW-sE)lkTm(DTrZ8UnI?TA!M80WCU(NnJT};`MwE!(3qkXr77=#e;$e)0sw(?fHGQl zNck1G)P~=;5NhxnDx_uRza>@7?10v6dQxlHASQ8E%R`-kHV0v{+`lL``hD{Nlm-nI z|6=|Jzec^3y%-F3y;V9Q1Sz<83Uwh&`gG0giJ3}iB6pf9W)2#?Z-i6q1N#bzFXo?E zD;Aj?!Uiy^eHd|>FceH#S4-?Mqh_Fx)pVR6W&=~MS2OY~bct}uw)*MI-`NGlP-^6#L7pXmAffs7~)E5K%&p65j!N`$#3D+ps&W6ZC(x0$Yp96dZ_^{~LJRzi92;*%>JgWVUp!2~ z$-66_OpN5@(a#&#xY}PF#hhx#`Mb5VjCR}LlhT!}P%i%lo^m!S#L_8SrRXi>W6mm8 z7dmK@Y{%^P&CSvut#x*NslZKP*4n}5SZoYvQ6p9T+s$`evr<^dq1KyLAL~q!7z(tM zy>&&V-m@Byb8v9DMbR(bMQ9s6Y;myK3x(5x27Hg*D{o8KOYXD^AsnDZTQ%_|+jk2; zp>;jD{S8jN{X-_d_vMew)EjHQbi!Y{WDh6yUU-!fuY-+U4%VfyxI0M_r?Xg^fx_R= z=vo`wnzf3PE6xDAWb65$`vL!Xdyvz3(FfAPo1U4^zl2H6;Zw(1X&y7#9c&twJ$Q5c zr$@-rsil={v~k~^F4QZIJnhQP#OrKF9eV1cnG@w3AjN~xCcuzyYAF2dd+Ya?^T z(xW+y>0yB(OV9F!h}s;6(dUPHC0riKNyBn$OQs#`j{4UH5x0D-Pi?4yB_Uc4;cUsd zKYYUQv5Il`pQ82FtyGzt`urA?WEGPG$5;A+W@gHQ18%aWv{@4%CHXK0Y=M-t_$zbT zwJmv_8Y$Q%=|+lXI_Db5=4piSC(ZlEy*5Cvm zH+qXRWiMnhW)7m;!;cppe^^S);A~_VCT6(y5$1%$QPl{ZbTmcb+oGdds6!a(JZhZN zlLw#B=vh5(z*vtraD{Kb#R?muDWdN8f}9eg7tJ`)D-yd!*IF{@Z;(=b^IlF$W(Gcz zN@!>uMagq(b7o3ok5`v+tohTt@VUMsHBU3knP+#*n2`=+$J;5X{of6Kq3rO6u{U|X z(Lu+Z_#sQ-9H{qQQI%~;ynBV;5q_A|U-TB`+mTlh4$k3FErQO>Hx~R+&+#7yiTJ&f z;Zk#Uc?YqHS6j@gBM-l7xM<%tf9_70B7*1lvX)fM>8<1lQm`<_gU_0aww9Wb=^shI zyN|N6#bG7DNb&U8G#m6=+yy%d(RDr-ouNhRCpYmj^}m$p^jp1gtqwtbTXrr!g-CD0 zi2`}MAaI9lpVorK3Z;gPZFasfxJm!LtpP!D4F)~k>&584Je#o$(Or}HbrUnZ+g=q8%B z4kZp&`0+3EeH+J{$_m_=A^67u>D5FrjE-9jrQX^z?wn7lIWPOUr$Et!mtAQl6>(wb z&PL&k*~f521>{B#lNaX?d)~Pj;@hZ6=WbgWR#C`vpg{Pgjc*5aDr}KVZE;JSUIv0#hDHWyR zYKZDB)1zOZ`mW23Rh3$_uq|ALiNf!@p-Hm=9+fCSBX`iCV8*5h%b)+0rvJ=gdP^$n z3bt^wOG~bb$K;Aru4_s(4J55AXEL_Xd#DYm`m>%h2V;6H(D=#iIs<%|hUa}Q+of}Cv467_X`ek0TIO8q7+v(wZ z|A~S-2{~SljXyh0mDIXpUmYITBRR$hMnCRoMmHeY%<3Uhu8%;_dr$d$=;I6XhLy z`9GvAj)n(;?}1ZbjFqYm%XR8#S?zT&!~IV z-V?IrP)K{*$;#8Da~km5Z^PDjeT%M|WDbhPZI5g+9O{il_%z8Y#W9<;Od7c@zr^Rh z1SmtZAlfLSY?U)p=9%qb5hB#rFAa zl2LQF#dOwa++P1uWeO_gDp?#R%5_o7Ph;m2Ty=!|jlQ=B!B$_^Yz@s%|C-D1ODIuM zf=T~Aii%8`pL~{tk(7En*@1O8{*j;W<%`AIL7D0jK9(lf{)LtA9#%50Xd|>FabRbe z)Cn*KhZBnZ&JBR#HPa*Y6gQ+_1J;%7Fv-ozOt(t1ncp&mrIxRjJlU547}I@XYsjO2 z{7nb+NOL`AOt|*nfE^34iTHTpAK1&!0QMMG-ts`fpg~gl_cvf-MJ|7{hB<;o4W9@> z|NZ}>0l87PXT_T@2f5Z?H3#9(xp!#UWjAnjKd_-Ty67$Elf4J5DB(pGemN{-0l3oU zqiTe|e*hB|C4kAkUiRxCe2oO;!TS0*d>w>8mh=CAkx)2j%!59)1IE^${*osz4aO>T zGEb!xKuy&IAA@D-12IaJXKsqqJinZ-x^wmV{^#G=-&>y9WFX-=7Nn^EnG=_?mOU()sEwMXsf3+Qob; z<)`AyW=l*WfAd{{QPZ^JDNoY2eGpqV@hV0!9Mz1qyz5Q3GMASb_zf0{x$K}uyefVD z|L`p@zp+xttO;^AN(4;YJM-fbn&d}OkB1Yd|4i_ K+s`yT68m4dwC~dZ literal 0 HcmV?d00001 diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 4deb85291b..5053eed3e4 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -184,6 +184,21 @@ There are two scripts to interact with controller manager from launch files: -c CONTROLLER_MANAGER, --controller-manager CONTROLLER_MANAGER Name of the controller manager ROS node +rqt_controller_manager +---------------------- +A GUI tool to interact with the controller manager services to be able to switch the lifecycle states of the controllers as well as the hardware components. + +.. image:: images/rqt_controller_manager.png + +It can be launched independently using the following command or as rqt plugin. + +.. code-block:: console + + ros2 run rqt_controller_manager rqt_controller_manager + + * Double-click on a controller or hardware component to show the additional info. + * Right-click on a controller or hardware component to show a context menu with options for lifecycle management. + Using the Controller Manager in a Process ----------------------------------------- diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp index 845fa2dee0..4865c1a7a6 100644 --- a/controller_manager/include/controller_manager/controller_manager.hpp +++ b/controller_manager/include/controller_manager/controller_manager.hpp @@ -193,7 +193,24 @@ class ControllerManager : public rclcpp::Node // the executor (see issue #260). // rclcpp::CallbackGroup::SharedPtr deterministic_callback_group_; - // Per controller update rate support + /// Interface for external components to check if Resource Manager is initialized. + /** + * Checks if components in Resource Manager are loaded and initialized. + * \returns true if they are initialized, false otherwise. + */ + CONTROLLER_MANAGER_PUBLIC + bool is_resource_manager_initialized() const + { + return resource_manager_ && resource_manager_->are_components_initialized(); + } + + /// Update rate of the main control loop in the controller manager. + /** + * Update rate of the main control loop in the controller manager. + * The method is used for per-controller update rate support. + * + * \returns update rate of the controller manager. + */ CONTROLLER_MANAGER_PUBLIC unsigned int get_update_rate() const; @@ -556,6 +573,9 @@ class ControllerManager : public rclcpp::Node std::vector activate_command_interface_request_, deactivate_command_interface_request_; + std::map> controller_chained_reference_interfaces_cache_; + std::map> controller_chained_state_interfaces_cache_; + std::string robot_description_; rclcpp::Subscription::SharedPtr robot_description_subscription_; diff --git a/controller_manager/package.xml b/controller_manager/package.xml index e2aa998332..d85c34f2d8 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.11.0 + 4.12.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index c4efe9ed95..9fc8d442d7 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -83,11 +83,11 @@ bool controller_name_compare(const controller_manager::ControllerSpec & a, const return a.info.name == name; } -/// Checks if a command interface belongs to a controller based on its prefix. +/// Checks if an interface belongs to a controller based on its prefix. /** - * A command interface can be provided by a controller in which case is called "reference" - * interface. - * This means that the @interface_name starts with the name of a controller. + * A State/Command interface can be provided by a controller in which case is called + * "state/reference" interface. This means that the @interface_name starts with the name of a + * controller. * * \param[in] interface_name to be found in the map. * \param[in] controllers list of controllers to compare their names to interface's prefix. @@ -95,7 +95,7 @@ bool controller_name_compare(const controller_manager::ControllerSpec & a, const * @interface_name belongs to. * \return true if interface has a controller name as prefix, false otherwise. */ -bool command_interface_is_reference_interface_of_controller( +bool is_interface_a_chained_interface( const std::string interface_name, const std::vector & controllers, controller_manager::ControllersListIterator & following_controller_it) @@ -125,8 +125,8 @@ bool command_interface_is_reference_interface_of_controller( { RCLCPP_DEBUG( rclcpp::get_logger("ControllerManager::utils"), - "Required command interface '%s' with prefix '%s' is not reference interface.", - interface_name.c_str(), interface_prefix.c_str()); + "Required interface '%s' with prefix '%s' is not a chain interface.", interface_name.c_str(), + interface_prefix.c_str()); return false; } @@ -169,7 +169,6 @@ void controller_chain_spec_cleanup( } ctrl_chain_spec.erase(controller); } - } // namespace namespace controller_manager @@ -187,8 +186,8 @@ ControllerManager::ControllerManager( std::shared_ptr executor, const std::string & manager_node_name, const std::string & node_namespace, const rclcpp::NodeOptions & options) : rclcpp::Node(manager_node_name, node_namespace, options), - resource_manager_(std::make_unique( - update_rate_, this->get_node_clock_interface())), + resource_manager_( + std::make_unique(this->get_node_clock_interface())), diagnostics_updater_(this), executor_(executor), loader_(std::make_shared>( @@ -216,7 +215,13 @@ ControllerManager::ControllerManager( "[Deprecated] Passing the robot description parameter directly to the control_manager node " "is deprecated. Use the 'robot_description' topic from 'robot_state_publisher' instead."); init_resource_manager(robot_description_); - init_services(); + if (is_resource_manager_initialized()) + { + RCLCPP_WARN( + get_logger(), + "You have to restart the framework when using robot description from parameter!"); + init_services(); + } } diagnostics_updater_.setHardwareID("ros2_control"); @@ -243,7 +248,7 @@ ControllerManager::ControllerManager( RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value."); } - if (resource_manager_->is_urdf_already_loaded()) + if (is_resource_manager_initialized()) { init_services(); } @@ -271,36 +276,32 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String & RCLCPP_INFO(get_logger(), "Received robot description from topic."); RCLCPP_DEBUG( get_logger(), "'Content of robot description file: %s", robot_description.data.c_str()); - // TODO(mamueluth): errors should probably be caught since we don't want controller_manager node - // to die if a non valid urdf is passed. However, should maybe be fine tuned. - try + robot_description_ = robot_description.data; + if (is_resource_manager_initialized()) { - robot_description_ = robot_description.data; - if (resource_manager_->is_urdf_already_loaded()) - { - RCLCPP_WARN( - get_logger(), - "ResourceManager has already loaded an urdf file. Ignoring attempt to reload a robot " - "description file."); - return; - } - init_resource_manager(robot_description_); - init_services(); + RCLCPP_WARN( + get_logger(), + "ResourceManager has already loaded an urdf file. Ignoring attempt to reload a robot " + "description file."); + return; } - catch (std::runtime_error & e) + init_resource_manager(robot_description_); + if (is_resource_manager_initialized()) { - RCLCPP_ERROR_STREAM( - get_logger(), - "The published robot description file (urdf) seems not to be genuine. The following error " - "was caught:" - << e.what()); + init_services(); } } void ControllerManager::init_resource_manager(const std::string & robot_description) { - // TODO(destogl): manage this when there is an error - CM should not die because URDF is wrong... - resource_manager_->load_urdf(robot_description); + if (!resource_manager_->load_and_initialize_components(robot_description, update_rate_)) + { + RCLCPP_WARN( + get_logger(), + "Could not load and initialize hardware. Please check previous output for more details. " + "After you have corrected your URDF, try to publish robot description again."); + return; + } // Get all components and if they are not defined in parameters activate them automatically auto components_to_activate = resource_manager_->get_components_status(); @@ -740,16 +741,20 @@ controller_interface::return_type ControllerManager::configure_controller( get_logger(), "Controller '%s' is chainable. Interfaces are being exported to resource manager.", controller_name.c_str()); - auto interfaces = controller->export_reference_interfaces(); - if (interfaces.empty()) + auto state_interfaces = controller->export_state_interfaces(); + auto ref_interfaces = controller->export_reference_interfaces(); + if (ref_interfaces.empty() && state_interfaces.empty()) { // TODO(destogl): Add test for this! RCLCPP_ERROR( - get_logger(), "Controller '%s' is chainable, but does not export any reference interfaces.", + get_logger(), + "Controller '%s' is chainable, but does not export any state or reference interfaces.", controller_name.c_str()); return controller_interface::return_type::ERROR; } - resource_manager_->import_controller_reference_interfaces(controller_name, interfaces); + resource_manager_->import_controller_reference_interfaces(controller_name, ref_interfaces); + resource_manager_->import_controller_exported_state_interfaces( + controller_name, state_interfaces); } // let's update the list of following and preceding controllers @@ -758,24 +763,28 @@ controller_interface::return_type ControllerManager::configure_controller( for (const auto & cmd_itf : cmd_itfs) { controller_manager::ControllersListIterator ctrl_it; - if (command_interface_is_reference_interface_of_controller(cmd_itf, controllers, ctrl_it)) + if (is_interface_a_chained_interface(cmd_itf, controllers, ctrl_it)) { add_element_to_list( controller_chain_spec_[controller_name].following_controllers, ctrl_it->info.name); add_element_to_list( controller_chain_spec_[ctrl_it->info.name].preceding_controllers, controller_name); + add_element_to_list( + controller_chained_reference_interfaces_cache_[ctrl_it->info.name], controller_name); } } // This is needed when we start exporting the state interfaces from the controllers for (const auto & state_itf : state_itfs) { controller_manager::ControllersListIterator ctrl_it; - if (command_interface_is_reference_interface_of_controller(state_itf, controllers, ctrl_it)) + if (is_interface_a_chained_interface(state_itf, controllers, ctrl_it)) { add_element_to_list( controller_chain_spec_[controller_name].preceding_controllers, ctrl_it->info.name); add_element_to_list( controller_chain_spec_[ctrl_it->info.name].following_controllers, controller_name); + add_element_to_list( + controller_chained_state_interfaces_cache_[ctrl_it->info.name], controller_name); } } @@ -835,6 +844,7 @@ void ControllerManager::clear_requests() // state without the controller being in active state for (const auto & controller_name : to_chained_mode_request_) { + resource_manager_->make_controller_exported_state_interfaces_unavailable(controller_name); resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); } to_chained_mode_request_.clear(); @@ -1116,6 +1126,14 @@ controller_interface::return_type ControllerManager::switch_controller( break; } + // Check after the check if the activate and deactivate list is empty or not + if (activate_request_.empty() && deactivate_request_.empty()) + { + RCLCPP_INFO(get_logger(), "Empty activate and deactivate list, not requesting switch"); + clear_requests(); + return controller_interface::return_type::OK; + } + for (const auto & controller : controllers) { auto to_chained_mode_list_it = std::find( @@ -1427,6 +1445,8 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::add_co // initialize the data for the controller chain spec once it is loaded. It is needed, so when we // sort the controllers later, they will be added to the list controller_chain_spec_[controller.info.name] = ControllerChainSpec(); + controller_chained_state_interfaces_cache_[controller.info.name] = {}; + controller_chained_reference_interfaces_cache_[controller.info.name] = {}; executor_->add_node(controller.c->get_node()->get_node_base_interface()); to.emplace_back(controller); @@ -1472,6 +1492,7 @@ void ControllerManager::deactivate_controllers( // deactivation if (controller->is_chainable()) { + resource_manager_->make_controller_exported_state_interfaces_unavailable(controller_name); resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); } if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) @@ -1680,6 +1701,8 @@ void ControllerManager::activate_controllers( // if it is a chainable controller, make the reference interfaces available on activation if (controller->is_chainable()) { + // make all the exported interfaces of the controller available + resource_manager_->make_controller_exported_state_interfaces_available(controller_name); resource_manager_->make_controller_reference_interfaces_available(controller_name); } @@ -1774,13 +1797,23 @@ void ControllerManager::list_controllers_srv_cb( { auto references = resource_manager_->get_controller_reference_interface_names(controllers[i].info.name); + auto exported_state_interfaces = + resource_manager_->get_controller_exported_state_interface_names( + controllers[i].info.name); controller_state.reference_interfaces.reserve(references.size()); + controller_state.exported_state_interfaces.reserve(exported_state_interfaces.size()); for (const auto & reference : references) { const std::string prefix_name = controllers[i].c->get_node()->get_name(); const std::string interface_name = reference.substr(prefix_name.size() + 1); controller_state.reference_interfaces.push_back(interface_name); } + for (const auto & state_interface : exported_state_interfaces) + { + const std::string prefix_name = controllers[i].c->get_node()->get_name(); + const std::string interface_name = state_interface.substr(prefix_name.size() + 1); + controller_state.exported_state_interfaces.push_back(interface_name); + } } } response->controller.push_back(controller_state); @@ -2406,12 +2439,16 @@ void ControllerManager::propagate_deactivation_of_chained_mode( break; } - for (const auto & cmd_itf_name : controller.c->command_interface_configuration().names) + const auto ctrl_cmd_itf_names = controller.c->command_interface_configuration().names; + const auto ctrl_state_itf_names = controller.c->state_interface_configuration().names; + auto ctrl_itf_names = ctrl_cmd_itf_names; + ctrl_itf_names.insert( + ctrl_itf_names.end(), ctrl_state_itf_names.begin(), ctrl_state_itf_names.end()); + for (const auto & ctrl_itf_name : ctrl_itf_names) { // controller that 'cmd_tf_name' belongs to ControllersListIterator following_ctrl_it; - if (command_interface_is_reference_interface_of_controller( - cmd_itf_name, controllers, following_ctrl_it)) + if (is_interface_a_chained_interface(ctrl_itf_name, controllers, following_ctrl_it)) { // currently iterated "controller" is preceding controller --> add following controller // with matching interface name to "from" chained mode list (if not already in it) @@ -2440,12 +2477,21 @@ controller_interface::return_type ControllerManager::check_following_controllers get_logger(), "Checking following controllers of preceding controller with name '%s'.", controller_it->info.name.c_str()); - for (const auto & cmd_itf_name : controller_it->c->command_interface_configuration().names) + const auto controller_cmd_interfaces = controller_it->c->command_interface_configuration().names; + const auto controller_state_interfaces = controller_it->c->state_interface_configuration().names; + // get all interfaces of the controller + auto controller_interfaces = controller_cmd_interfaces; + controller_interfaces.insert( + controller_interfaces.end(), controller_state_interfaces.begin(), + controller_state_interfaces.end()); + for (const auto & ctrl_itf_name : controller_interfaces) { + RCLCPP_ERROR( + get_logger(), "Checking interface '%s' of controller '%s'.", ctrl_itf_name.c_str(), + controller_it->info.name.c_str()); ControllersListIterator following_ctrl_it; // Check if interface if reference interface and following controller exist. - if (!command_interface_is_reference_interface_of_controller( - cmd_itf_name, controllers, following_ctrl_it)) + if (!is_interface_a_chained_interface(ctrl_itf_name, controllers, following_ctrl_it)) { continue; } @@ -2465,9 +2511,9 @@ controller_interface::return_type ControllerManager::check_following_controllers { RCLCPP_WARN( get_logger(), - "No reference interface '%s' exist, since the following controller with name '%s' " - "is not chainable.", - cmd_itf_name.c_str(), following_ctrl_it->info.name.c_str()); + "No state/reference interface '%s' exist, since the following controller with name " + "'%s' is not chainable.", + ctrl_itf_name.c_str(), following_ctrl_it->info.name.c_str()); return controller_interface::return_type::ERROR; } @@ -2520,14 +2566,23 @@ controller_interface::return_type ControllerManager::check_following_controllers following_ctrl_it->info.name); if (found_it == to_chained_mode_request_.end()) { - to_chained_mode_request_.push_back(following_ctrl_it->info.name); // if it is a chainable controller, make the reference interfaces available on preactivation // (This is needed when you activate a couple of chainable controller altogether) - resource_manager_->make_controller_reference_interfaces_available( + // make all the exported interfaces of the controller available + resource_manager_->make_controller_exported_state_interfaces_available( following_ctrl_it->info.name); - RCLCPP_DEBUG( - get_logger(), "Adding controller '%s' in 'to chained mode' request.", - following_ctrl_it->info.name.c_str()); + if ( + std::find( + controller_cmd_interfaces.begin(), controller_cmd_interfaces.end(), ctrl_itf_name) != + controller_cmd_interfaces.end()) + { + resource_manager_->make_controller_reference_interfaces_available( + following_ctrl_it->info.name); + to_chained_mode_request_.push_back(following_ctrl_it->info.name); + RCLCPP_DEBUG( + get_logger(), "Adding controller '%s' in 'to chained mode' request.", + following_ctrl_it->info.name.c_str()); + } } } else @@ -2560,79 +2615,63 @@ controller_interface::return_type ControllerManager::check_preceeding_controller return controller_interface::return_type::OK; } - if (!controller_it->c->is_in_chained_mode()) - { - RCLCPP_DEBUG( - get_logger(), - "Controller with name '%s' is chainable but not in chained mode. " - "No need to do any checks of preceding controllers when stopping it.", - controller_it->info.name.c_str()); - return controller_interface::return_type::OK; - } - RCLCPP_DEBUG( get_logger(), "Checking preceding controller of following controller with name '%s'.", controller_it->info.name.c_str()); - for (const auto & ref_itf_name : - resource_manager_->get_controller_reference_interface_names(controller_it->info.name)) + auto preceeding_controllers_list = + controller_chained_state_interfaces_cache_[controller_it->info.name]; + preceeding_controllers_list.insert( + preceeding_controllers_list.end(), + controller_chained_reference_interfaces_cache_[controller_it->info.name].cbegin(), + controller_chained_reference_interfaces_cache_[controller_it->info.name].cend()); + + for (const auto & preceeding_controller : preceeding_controllers_list) { - std::vector preceding_controllers_using_ref_itf; + RCLCPP_DEBUG(get_logger(), "\t Preceding controller : '%s'.", preceeding_controller.c_str()); + auto found_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, preceeding_controller)); - // TODO(destogl): This data could be cached after configuring controller into a map for faster - // access here - for (auto preceding_ctrl_it = controllers.begin(); preceding_ctrl_it != controllers.end(); - ++preceding_ctrl_it) + if (found_it != controllers.end()) { - const auto preceding_ctrl_cmd_itfs = - preceding_ctrl_it->c->command_interface_configuration().names; - - // if controller is not preceding go the next one - if ( - std::find(preceding_ctrl_cmd_itfs.begin(), preceding_ctrl_cmd_itfs.end(), ref_itf_name) == - preceding_ctrl_cmd_itfs.end()) - { - continue; - } - - // check if preceding controller will be activated if ( - is_controller_inactive(preceding_ctrl_it->c) && - std::find( - activate_request_.begin(), activate_request_.end(), preceding_ctrl_it->info.name) != + is_controller_inactive(found_it->c) && + std::find(activate_request_.begin(), activate_request_.end(), preceeding_controller) != activate_request_.end()) { RCLCPP_WARN( get_logger(), "Could not deactivate controller with name '%s' because " - "preceding controller with name '%s' will be activated. ", - controller_it->info.name.c_str(), preceding_ctrl_it->info.name.c_str()); + "preceding controller with name '%s' is inactive and will be activated.", + controller_it->info.name.c_str(), preceeding_controller.c_str()); return controller_interface::return_type::ERROR; } - // check if preceding controller will not be deactivated - else if ( - is_controller_active(preceding_ctrl_it->c) && - std::find( - deactivate_request_.begin(), deactivate_request_.end(), preceding_ctrl_it->info.name) == + if ( + is_controller_active(found_it->c) && + std::find(deactivate_request_.begin(), deactivate_request_.end(), preceeding_controller) == deactivate_request_.end()) { RCLCPP_WARN( get_logger(), "Could not deactivate controller with name '%s' because " "preceding controller with name '%s' is active and will not be deactivated.", - controller_it->info.name.c_str(), preceding_ctrl_it->info.name.c_str()); + controller_it->info.name.c_str(), preceeding_controller.c_str()); return controller_interface::return_type::ERROR; } - // TODO(destogl): this should be discussed how to it the best - just a placeholder for now - // else if ( - // strictness == - // controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN) - // { - // // insert to the begin of activate request list to be activated before preceding controller - // activate_request_.insert(activate_request_.begin(), preceding_ctrl_name); - // } } } + + // TODO(destogl): this should be discussed how to it the best - just a placeholder for now + // else if ( + // strictness == + // controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN) + // { + // // insert to the begin of activate request list to be activated before preceding + // controller + // activate_request_.insert(activate_request_.begin(), preceding_ctrl_name); + // } + return controller_interface::return_type::OK; } 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 d21957a0b4..e43f2a13a1 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp @@ -52,6 +52,13 @@ TestChainableController::state_interface_configuration() const get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE || get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { + auto state_iface_cfg = state_iface_cfg_; + if (imu_sensor_) + { + auto imu_interfaces = imu_sensor_->get_state_interface_names(); + state_iface_cfg.names.insert( + state_iface_cfg.names.end(), imu_interfaces.begin(), imu_interfaces.end()); + } return state_iface_cfg_; } else @@ -96,6 +103,20 @@ controller_interface::return_type TestChainableController::update_and_write_comm { command_interfaces_[i].set_value(reference_interfaces_[i] - state_interfaces_[i].get_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; + } + // If there is no command interface and if there is a state interface then just forward the same + // value as in the state interface + for (size_t i = 0; i < exported_state_interface_names_.size() && i < state_interfaces_.size() && + command_interfaces_.empty(); + ++i) + { + state_interfaces_values_[i] = state_interfaces_[i].get_value(); + } return controller_interface::return_type::OK; } @@ -150,6 +171,20 @@ CallbackReturn TestChainableController::on_cleanup( return CallbackReturn::SUCCESS; } +std::vector +TestChainableController::on_export_state_interfaces() +{ + std::vector state_interfaces; + + for (size_t i = 0; i < exported_state_interface_names_.size(); ++i) + { + state_interfaces.push_back(hardware_interface::StateInterface( + get_node()->get_name(), exported_state_interface_names_[i], &state_interfaces_values_[i])); + } + + return state_interfaces; +} + std::vector TestChainableController::on_export_reference_interfaces() { @@ -184,6 +219,31 @@ void TestChainableController::set_reference_interface_names( reference_interfaces_.resize(reference_interface_names.size(), 0.0); } +void TestChainableController::set_exported_state_interface_names( + const std::vector & state_interface_names) +{ + exported_state_interface_names_ = state_interface_names; + + state_interfaces_values_.resize(exported_state_interface_names_.size(), 0.0); +} + +void TestChainableController::set_imu_sensor_name(const std::string & name) +{ + if (!name.empty()) + { + imu_sensor_ = std::make_unique(name); + } +} + +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()); + } + return state_intr_data; +} } // namespace test_chainable_controller #include "pluginlib/class_list_macros.hpp" diff --git a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp index 5925ed8d11..f4f59ad9df 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp @@ -23,6 +23,7 @@ #include "controller_manager/visibility_control.h" #include "rclcpp/subscription.hpp" #include "realtime_tools/realtime_buffer.h" +#include "semantic_components/imu_sensor.hpp" #include "std_msgs/msg/float64_multi_array.hpp" namespace test_chainable_controller @@ -35,6 +36,7 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface constexpr char TEST_CONTROLLER_NAME[] = "test_chainable_controller_name"; // corresponds to the name listed within the pluginlib xml constexpr char TEST_CONTROLLER_CLASS_NAME[] = "controller_manager/test_chainable_controller"; +constexpr double CONTROLLER_DT = 0.001; class TestChainableController : public controller_interface::ChainableControllerInterface { public: @@ -60,6 +62,9 @@ class TestChainableController : public controller_interface::ChainableController CONTROLLER_MANAGER_PUBLIC CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override; + CONTROLLER_MANAGER_PUBLIC + std::vector on_export_state_interfaces() override; + CONTROLLER_MANAGER_PUBLIC std::vector on_export_reference_interfaces() override; @@ -80,10 +85,21 @@ class TestChainableController : public controller_interface::ChainableController CONTROLLER_MANAGER_PUBLIC void set_reference_interface_names(const std::vector & reference_interface_names); + CONTROLLER_MANAGER_PUBLIC + void set_exported_state_interface_names(const std::vector & state_interface_names); + + CONTROLLER_MANAGER_PUBLIC + void set_imu_sensor_name(const std::string & name); + + CONTROLLER_MANAGER_PUBLIC + std::vector get_state_interface_data() const; + size_t internal_counter; controller_interface::InterfaceConfiguration cmd_iface_cfg_; controller_interface::InterfaceConfiguration state_iface_cfg_; std::vector reference_interface_names_; + std::vector exported_state_interface_names_; + std::unique_ptr imu_sensor_; realtime_tools::RealtimeBuffer> rt_command_ptr_; rclcpp::Subscription::SharedPtr joints_command_subscriber_; diff --git a/controller_manager/test/test_controller/test_controller.cpp b/controller_manager/test/test_controller/test_controller.cpp index 8f120bbd47..625d7ed90f 100644 --- a/controller_manager/test/test_controller/test_controller.cpp +++ b/controller_manager/test/test_controller/test_controller.cpp @@ -128,6 +128,16 @@ void TestController::set_state_interface_configuration( state_iface_cfg_ = cfg; } +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()); + } + return state_intr_data; +} + } // namespace test_controller #include "pluginlib/class_list_macros.hpp" diff --git a/controller_manager/test/test_controller/test_controller.hpp b/controller_manager/test/test_controller/test_controller.hpp index 368aeae4a8..bf183c7bad 100644 --- a/controller_manager/test/test_controller/test_controller.hpp +++ b/controller_manager/test/test_controller/test_controller.hpp @@ -66,6 +66,9 @@ class TestController : public controller_interface::ControllerInterface CONTROLLER_MANAGER_PUBLIC void set_state_interface_configuration(const controller_interface::InterfaceConfiguration & cfg); + CONTROLLER_MANAGER_PUBLIC + std::vector get_state_interface_data() const; + const std::string & getRobotDescription() const; unsigned int internal_counter = 0; diff --git a/controller_manager/test/test_controller_manager_srvs.cpp b/controller_manager/test/test_controller_manager_srvs.cpp index 24cd30bc06..4fdfe3fb9f 100644 --- a/controller_manager/test/test_controller_manager_srvs.cpp +++ b/controller_manager/test/test_controller_manager_srvs.cpp @@ -980,34 +980,37 @@ TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers) // add controllers /// @todo add controllers in random order /// For now, adding the ordered case to see that current sorting doesn't change order - cm_->add_controller( - test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_6, TEST_CHAINED_CONTROLLER_6, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_7, TEST_CHAINED_CONTROLLER_7, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_controller_1, TEST_CONTROLLER_1, test_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_4, TEST_CHAINED_CONTROLLER_4, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_controller_2, TEST_CONTROLLER_2, test_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_8, TEST_CHAINED_CONTROLLER_8, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + { + ControllerManagerRunner cm_runner(this); + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_6, TEST_CHAINED_CONTROLLER_6, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_7, TEST_CHAINED_CONTROLLER_7, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller_1, TEST_CONTROLLER_1, test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_4, TEST_CHAINED_CONTROLLER_4, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller_2, TEST_CONTROLLER_2, test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_8, TEST_CHAINED_CONTROLLER_8, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + } // get controller list before configure auto result = call_service_and_wait(*client, request, srv_executor); @@ -1233,40 +1236,40 @@ TEST_F(TestControllerManagerSrvs, list_large_number_of_controllers_with_chains) // add controllers /// @todo add controllers in random order /// For now, adding the ordered case to see that current sorting doesn't change order - cm_->add_controller( - test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_6, TEST_CHAINED_CONTROLLER_6, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_7, TEST_CHAINED_CONTROLLER_7, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_controller_1, TEST_CONTROLLER_1, test_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_4, TEST_CHAINED_CONTROLLER_4, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_controller_2, TEST_CONTROLLER_2, test_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_8, TEST_CHAINED_CONTROLLER_8, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - cm_->add_controller( - test_chained_controller_9, TEST_CHAINED_CONTROLLER_9, - test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); - { ControllerManagerRunner cm_runner(this); + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_6, TEST_CHAINED_CONTROLLER_6, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_7, TEST_CHAINED_CONTROLLER_7, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller_1, TEST_CONTROLLER_1, test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_4, TEST_CHAINED_CONTROLLER_4, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller_2, TEST_CONTROLLER_2, test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_8, TEST_CHAINED_CONTROLLER_8, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_9, TEST_CHAINED_CONTROLLER_9, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + for (auto random_ctrl : random_controllers_list) { cm_->add_controller( diff --git a/controller_manager/test/test_controller_manager_urdf_passing.cpp b/controller_manager/test/test_controller_manager_urdf_passing.cpp index 5c2ebd14f6..5db4cfc683 100644 --- a/controller_manager/test/test_controller_manager_urdf_passing.cpp +++ b/controller_manager/test/test_controller_manager_urdf_passing.cpp @@ -29,11 +29,13 @@ class TestableControllerManager : public controller_manager::ControllerManager { friend TestControllerManagerWithTestableCM; - FRIEND_TEST(TestControllerManagerWithTestableCM, initial_no_load_urdf_called); - FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback); - FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed); - FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback); - FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback); + FRIEND_TEST( + TestControllerManagerWithTestableCM, initial_no_load_and_initialize_components_called); + FRIEND_TEST( + TestControllerManagerWithTestableCM, load_and_initialize_components_called_after_callback); + FRIEND_TEST( + TestControllerManagerWithTestableCM, + expect_to_failure_when_invalid_urdf_is_given_and_be_able_to_submit_new_robot_description); public: TestableControllerManager( @@ -59,29 +61,36 @@ class TestControllerManagerWithTestableCM } }; -TEST_P(TestControllerManagerWithTestableCM, initial_no_load_urdf_called) +TEST_P(TestControllerManagerWithTestableCM, initial_no_load_and_initialize_components_called) { - ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded()); + ASSERT_FALSE(cm_->resource_manager_->are_components_initialized()); } -TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_callback) +TEST_P(TestControllerManagerWithTestableCM, load_and_initialize_components_called_after_callback) { - ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded()); + ASSERT_FALSE(cm_->resource_manager_->are_components_initialized()); // mimic callback auto msg = std_msgs::msg::String(); msg.data = ros2_control_test_assets::minimal_robot_urdf; cm_->robot_description_callback(msg); - ASSERT_TRUE(cm_->resource_manager_->is_urdf_already_loaded()); + ASSERT_TRUE(cm_->resource_manager_->are_components_initialized()); } -TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed) +TEST_P( + TestControllerManagerWithTestableCM, + expect_to_failure_when_invalid_urdf_is_given_and_be_able_to_submit_new_robot_description) { - ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded()); - // mimic callback + ASSERT_FALSE(cm_->resource_manager_->are_components_initialized()); + // wrong urdf auto msg = std_msgs::msg::String(); - msg.data = ros2_control_test_assets::minimal_robot_missing_command_keys_urdf; + msg.data = ros2_control_test_assets::minimal_uninitializable_robot_urdf; + cm_->robot_description_callback(msg); + ASSERT_FALSE(cm_->resource_manager_->are_components_initialized()); + // correct urdf + msg = std_msgs::msg::String(); + msg.data = ros2_control_test_assets::minimal_robot_urdf; cm_->robot_description_callback(msg); - ASSERT_TRUE(cm_->resource_manager_->is_urdf_already_loaded()); + ASSERT_TRUE(cm_->resource_manager_->are_components_initialized()); } INSTANTIATE_TEST_SUITE_P( 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 e7517a0335..e1cdabbb03 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -131,6 +131,10 @@ class TestControllerChainingWithControllerManager diff_drive_controller = std::make_shared(); diff_drive_controller_two = std::make_shared(); position_tracking_controller = std::make_shared(); + position_tracking_controller_two = std::make_shared(); + odom_publisher_controller = std::make_shared(); + sensor_fusion_controller = std::make_shared(); + robot_localization_controller = std::make_shared(); // configure Left Wheel controller controller_interface::InterfaceConfiguration pid_left_cmd_ifs_cfg = { @@ -141,7 +145,7 @@ class TestControllerChainingWithControllerManager pid_left_wheel_controller->set_state_interface_configuration(pid_left_state_ifs_cfg); pid_left_wheel_controller->set_reference_interface_names({"velocity"}); - // configure Left Wheel controller + // configure Right Wheel controller controller_interface::InterfaceConfiguration pid_right_cmd_ifs_cfg = { controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_right/velocity"}}; controller_interface::InterfaceConfiguration pid_right_state_ifs_cfg = { @@ -160,11 +164,13 @@ class TestControllerChainingWithControllerManager diff_drive_controller->set_command_interface_configuration(diff_drive_cmd_ifs_cfg); diff_drive_controller->set_state_interface_configuration(diff_drive_state_ifs_cfg); diff_drive_controller->set_reference_interface_names({"vel_x", "vel_y", "rot_z"}); + diff_drive_controller->set_exported_state_interface_names({"odom_x", "odom_y"}); - // configure Diff Drive Two controller (Has same command interfaces ad Diff Drive controller) + // configure Diff Drive Two controller (Has same command interfaces as Diff Drive controller) diff_drive_controller_two->set_command_interface_configuration(diff_drive_cmd_ifs_cfg); diff_drive_controller_two->set_state_interface_configuration(diff_drive_state_ifs_cfg); diff_drive_controller_two->set_reference_interface_names({"vel_x", "vel_y", "rot_z"}); + diff_drive_controller_two->set_exported_state_interface_names({"odom_x", "odom_y"}); // configure Position Tracking controller controller_interface::InterfaceConfiguration position_tracking_cmd_ifs_cfg = { @@ -174,16 +180,51 @@ class TestControllerChainingWithControllerManager // in this simple example "vel_x" == "velocity left wheel" and "vel_y" == "velocity right wheel" position_tracking_controller->set_command_interface_configuration( position_tracking_cmd_ifs_cfg); + + // configure Odometry Publisher controller + controller_interface::InterfaceConfiguration odom_and_fusion_ifs_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(DIFF_DRIVE_CONTROLLER) + "/odom_x", + std::string(DIFF_DRIVE_CONTROLLER) + "/odom_y"}}; + odom_publisher_controller->set_state_interface_configuration(odom_and_fusion_ifs_cfg); + + // configure sensor fusion controller + sensor_fusion_controller->set_imu_sensor_name("base_imu"); + sensor_fusion_controller->set_state_interface_configuration(odom_and_fusion_ifs_cfg); + sensor_fusion_controller->set_exported_state_interface_names({"odom_x", "odom_y", "yaw"}); + + // configure Robot Localization controller + controller_interface::InterfaceConfiguration odom_ifs_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(SENSOR_FUSION_CONTROLLER) + "/odom_x", + std::string(SENSOR_FUSION_CONTROLLER) + "/odom_y", + std::string(SENSOR_FUSION_CONTROLLER) + "/yaw"}}; + robot_localization_controller->set_state_interface_configuration(odom_ifs_cfg); + robot_localization_controller->set_exported_state_interface_names({"actual_pose"}); + + // configure Position Tracking controller Two + controller_interface::InterfaceConfiguration position_tracking_state_ifs_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(ROBOT_LOCALIZATION_CONTROLLER) + "/actual_pose"}}; + // in this simple example "vel_x" == "velocity left wheel" and "vel_y" == "velocity right wheel" + position_tracking_controller_two->set_command_interface_configuration( + position_tracking_cmd_ifs_cfg); + position_tracking_controller_two->set_state_interface_configuration( + position_tracking_state_ifs_cfg); } void CheckIfControllersAreAddedCorrectly() { - EXPECT_EQ(5u, cm_->get_loaded_controllers().size()); + EXPECT_EQ(9u, cm_->get_loaded_controllers().size()); EXPECT_EQ(2, pid_left_wheel_controller.use_count()); EXPECT_EQ(2, pid_right_wheel_controller.use_count()); EXPECT_EQ(2, diff_drive_controller.use_count()); EXPECT_EQ(2, diff_drive_controller_two.use_count()); EXPECT_EQ(2, position_tracking_controller.use_count()); + EXPECT_EQ(2, sensor_fusion_controller.use_count()); + EXPECT_EQ(2, robot_localization_controller.use_count()); + EXPECT_EQ(2, odom_publisher_controller.use_count()); + EXPECT_EQ(2, position_tracking_controller_two.use_count()); EXPECT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, @@ -200,6 +241,18 @@ class TestControllerChainingWithControllerManager EXPECT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, position_tracking_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, + sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, + robot_localization_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, + position_tracking_controller_two->get_state().id()); } // order or controller configuration is not important therefore we can reuse the same method @@ -207,6 +260,7 @@ class TestControllerChainingWithControllerManager { // Store initial values of command interfaces size_t number_of_cmd_itfs = cm_->resource_manager_->command_interface_keys().size(); + size_t number_of_state_itfs = cm_->resource_manager_->state_interface_keys().size(); // configure chainable controller and check exported interfaces cm_->configure_controller(PID_LEFT_WHEEL); @@ -214,6 +268,7 @@ class TestControllerChainingWithControllerManager pid_left_wheel_controller->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 1); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs); for (const auto & interface : {"pid_left_wheel_controller/velocity"}) { EXPECT_TRUE(cm_->resource_manager_->command_interface_exists(interface)); @@ -226,6 +281,7 @@ class TestControllerChainingWithControllerManager pid_right_wheel_controller->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 2); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs); for (const auto & interface : {"pid_right_wheel_controller/velocity"}) { EXPECT_TRUE(cm_->resource_manager_->command_interface_exists(interface)); @@ -234,9 +290,14 @@ class TestControllerChainingWithControllerManager } cm_->configure_controller(DIFF_DRIVE_CONTROLLER); + for (auto & x : cm_->resource_manager_->available_state_interfaces()) + { + RCLCPP_ERROR_STREAM(cm_->get_logger(), x); + } EXPECT_EQ( diff_drive_controller->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 5); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 2); for (const auto & interface : {"diff_drive_controller/vel_x", "diff_drive_controller/vel_y", "diff_drive_controller/rot_z"}) @@ -245,12 +306,18 @@ class TestControllerChainingWithControllerManager EXPECT_FALSE(cm_->resource_manager_->command_interface_is_available(interface)); EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); } + for (const auto & interface : {"diff_drive_controller/odom_x", "diff_drive_controller/odom_y"}) + { + EXPECT_TRUE(cm_->resource_manager_->state_interface_exists(interface)); + EXPECT_FALSE(cm_->resource_manager_->state_interface_is_available(interface)); + } cm_->configure_controller(DIFF_DRIVE_CONTROLLER_TWO); EXPECT_EQ( diff_drive_controller_two->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 8); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 4); for (const auto & interface : {"diff_drive_controller/vel_x", "diff_drive_controller/vel_y", "diff_drive_controller/rot_z"}) @@ -259,31 +326,83 @@ class TestControllerChainingWithControllerManager EXPECT_FALSE(cm_->resource_manager_->command_interface_is_available(interface)); EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); } + for (const auto & interface : {"diff_drive_controller/odom_x", "diff_drive_controller/odom_y"}) + { + EXPECT_TRUE(cm_->resource_manager_->state_interface_exists(interface)); + EXPECT_FALSE(cm_->resource_manager_->state_interface_is_available(interface)); + } cm_->configure_controller(POSITION_TRACKING_CONTROLLER); EXPECT_EQ( position_tracking_controller->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 8); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 4); + + cm_->configure_controller(SENSOR_FUSION_CONTROLLER); + EXPECT_EQ( + position_tracking_controller->get_state().id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 8); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 7); + + cm_->configure_controller(ROBOT_LOCALIZATION_CONTROLLER); + EXPECT_EQ( + position_tracking_controller->get_state().id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 8); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 8); + + cm_->configure_controller(ODOM_PUBLISHER_CONTROLLER); + EXPECT_EQ( + position_tracking_controller->get_state().id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 8); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 8); + + cm_->configure_controller(POSITION_TRACKING_CONTROLLER_TWO); + EXPECT_EQ( + position_tracking_controller_two->get_state().id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + EXPECT_EQ(cm_->resource_manager_->command_interface_keys().size(), number_of_cmd_itfs + 8); + EXPECT_EQ(cm_->resource_manager_->state_interface_keys().size(), number_of_state_itfs + 8); } template < typename T, typename std::enable_if< std::is_convertible::value, T>::type * = nullptr> - void SetToChainedModeAndMakeReferenceInterfacesAvailable( + void SetToChainedModeAndMakeInterfacesAvailable( std::shared_ptr & controller, const std::string & controller_name, + const std::vector & exported_state_interfaces, const std::vector & reference_interfaces) { - controller->set_chained_mode(true); - EXPECT_TRUE(controller->is_in_chained_mode()); - // make reference interface command_interfaces available - cm_->resource_manager_->make_controller_reference_interfaces_available(controller_name); - for (const auto & interface : reference_interfaces) + if (!exported_state_interfaces.empty() || !reference_interfaces.empty()) { - EXPECT_TRUE(cm_->resource_manager_->command_interface_exists(interface)); - EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); - EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); + controller->set_chained_mode(true); + EXPECT_TRUE(controller->is_in_chained_mode()); + if (!reference_interfaces.empty()) + { + // make reference interface command_interfaces available + cm_->resource_manager_->make_controller_reference_interfaces_available(controller_name); + for (const auto & interface : reference_interfaces) + { + EXPECT_TRUE(cm_->resource_manager_->command_interface_exists(interface)); + EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); + EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); + } + } + if (!exported_state_interfaces.empty()) + { + // make state interface state_interfaces available + cm_->resource_manager_->make_controller_exported_state_interfaces_available( + controller_name); + for (const auto & interface : exported_state_interfaces) + { + EXPECT_TRUE(cm_->resource_manager_->state_interface_exists(interface)); + EXPECT_TRUE(cm_->resource_manager_->state_interface_is_available(interface)); + } + } } } @@ -309,11 +428,13 @@ class TestControllerChainingWithControllerManager { if (claimed_interfaces_from_hw) { - EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); + EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)) + << "The interface : " << interface << " should be available but it is not available"; } else { - EXPECT_FALSE(cm_->resource_manager_->command_interface_is_available(interface)); + EXPECT_FALSE(cm_->resource_manager_->command_interface_is_available(interface)) + << "The interface : " << interface << " shouldn't be available but it is available"; } EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); } @@ -357,10 +478,11 @@ class TestControllerChainingWithControllerManager std::shared_ptr & controller, const std::string & controller_name, const std::vector & claimed_command_itfs, size_t expected_internal_counter = 0u, const bool claimed_interfaces_from_hw = false, - const controller_interface::return_type expected_return = controller_interface::return_type::OK) + const controller_interface::return_type expected_return = controller_interface::return_type::OK, + const std::future_status expected_future_status = std::future_status::timeout) { switch_test_controllers( - {}, {controller_name}, test_param.strictness, std::future_status::timeout, expected_return); + {}, {controller_name}, test_param.strictness, expected_future_status, expected_return); check_after_de_activate( controller, claimed_command_itfs, expected_internal_counter, expected_return, true, claimed_interfaces_from_hw); @@ -388,10 +510,13 @@ class TestControllerChainingWithControllerManager cm_->resource_manager_->read(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); // check if all controllers are updated - ASSERT_EQ(position_tracking_controller->internal_counter, exp_internal_counter_pos_ctrl); - ASSERT_EQ(diff_drive_controller->internal_counter, exp_internal_counter_pos_ctrl + 2); - ASSERT_EQ(pid_left_wheel_controller->internal_counter, exp_internal_counter_pos_ctrl + 6); - ASSERT_EQ(pid_right_wheel_controller->internal_counter, exp_internal_counter_pos_ctrl + 4); + ASSERT_EQ(odom_publisher_controller->internal_counter, exp_internal_counter_pos_ctrl); + ASSERT_EQ(robot_localization_controller->internal_counter, exp_internal_counter_pos_ctrl + 2); + ASSERT_EQ(sensor_fusion_controller->internal_counter, exp_internal_counter_pos_ctrl + 4); + ASSERT_EQ(position_tracking_controller->internal_counter, exp_internal_counter_pos_ctrl + 6); + ASSERT_EQ(diff_drive_controller->internal_counter, exp_internal_counter_pos_ctrl + 8); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, exp_internal_counter_pos_ctrl + 12); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, exp_internal_counter_pos_ctrl + 10); // check if values are set properly in controllers ASSERT_EQ( @@ -407,12 +532,25 @@ class TestControllerChainingWithControllerManager 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); + EXP_STATE_ODOM_X = chained_estimate_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE); + EXP_STATE_ODOM_Y = chained_estimate_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE); + ASSERT_EQ(sensor_fusion_controller->state_interfaces_values_.size(), 3u); + ASSERT_EQ(robot_localization_controller->get_state_interface_data().size(), 3u); + ASSERT_EQ(robot_localization_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); + ASSERT_EQ(robot_localization_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); + ASSERT_EQ(odom_publisher_controller->get_state_interface_data().size(), 2u); + ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); + ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); + 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); // DiffDrive uses the same state ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_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); @@ -421,10 +559,17 @@ class TestControllerChainingWithControllerManager pid_right_wheel_controller->state_interfaces_[0].get_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); + // 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); } // check data propagation through controllers and if individual controllers are working double chained_ctrl_calculation(double reference, double state) { return reference - state; } + double chained_estimate_calculation(double reference, double state) + { + return (reference - state) * test_chainable_controller::CONTROLLER_DT; + } double hardware_calculation(double command) { return command / 2.0; } // set controllers' names @@ -433,6 +578,10 @@ class TestControllerChainingWithControllerManager static constexpr char DIFF_DRIVE_CONTROLLER[] = "diff_drive_controller"; static constexpr char DIFF_DRIVE_CONTROLLER_TWO[] = "diff_drive_controller_two"; static constexpr char POSITION_TRACKING_CONTROLLER[] = "position_tracking_controller"; + static constexpr char SENSOR_FUSION_CONTROLLER[] = "sensor_fusion_controller"; + static constexpr char ROBOT_LOCALIZATION_CONTROLLER[] = "robot_localization_controller"; + static constexpr char ODOM_PUBLISHER_CONTROLLER[] = "odometry_publisher_controller"; + static constexpr char POSITION_TRACKING_CONTROLLER_TWO[] = "position_tracking_controller_two"; const std::vector PID_LEFT_WHEEL_REFERENCE_INTERFACES = { "pid_left_wheel_controller/velocity"}; @@ -440,6 +589,11 @@ class TestControllerChainingWithControllerManager "pid_right_wheel_controller/velocity"}; const std::vector DIFF_DRIVE_REFERENCE_INTERFACES = { "diff_drive_controller/vel_x", "diff_drive_controller/vel_y", "diff_drive_controller/rot_z"}; + const std::vector DIFF_DRIVE_STATE_INTERFACES = { + "diff_drive_controller/odom_x", "diff_drive_controller/odom_y"}; + const std::vector SENSOR_FUSION_ESIMTATED_INTERFACES = { + "sensor_fusion_controller/odom_x", "sensor_fusion_controller/odom_y", + "sensor_fusion_controller/yaw"}; const std::vector PID_LEFT_WHEEL_CLAIMED_INTERFACES = {"wheel_left/velocity"}; const std::vector PID_RIGHT_WHEEL_CLAIMED_INTERFACES = {"wheel_right/velocity"}; @@ -453,7 +607,11 @@ class TestControllerChainingWithControllerManager std::shared_ptr pid_right_wheel_controller; std::shared_ptr diff_drive_controller; std::shared_ptr diff_drive_controller_two; + std::shared_ptr sensor_fusion_controller; + std::shared_ptr robot_localization_controller; + std::shared_ptr odom_publisher_controller; std::shared_ptr position_tracking_controller; + std::shared_ptr position_tracking_controller_two; testing::WithParamInterface::ParamType test_param; @@ -464,6 +622,8 @@ class TestControllerChainingWithControllerManager double EXP_RIGHT_WHEEL_HW_STATE = 0.0; double EXP_LEFT_WHEEL_REF = 0.0; double EXP_RIGHT_WHEEL_REF = 0.0; + double EXP_STATE_ODOM_X = 0.0; + double EXP_STATE_ODOM_Y = 0.0; // Expected behaviors struct used in chaining activation/deactivation tests struct ExpectedBehaviorStruct @@ -498,17 +658,32 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) cm_->add_controller( pid_right_wheel_controller, PID_RIGHT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); CheckIfControllersAreAddedCorrectly(); ConfigureAndCheckControllers(); - SetToChainedModeAndMakeReferenceInterfacesAvailable( - pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_REFERENCE_INTERFACES); - SetToChainedModeAndMakeReferenceInterfacesAvailable( - pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_REFERENCE_INTERFACES); - SetToChainedModeAndMakeReferenceInterfacesAvailable( - diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + pid_left_wheel_controller, PID_LEFT_WHEEL, {}, PID_LEFT_WHEEL_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + pid_right_wheel_controller, PID_RIGHT_WHEEL, {}, PID_RIGHT_WHEEL_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_STATE_INTERFACES, + DIFF_DRIVE_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, SENSOR_FUSION_ESIMTATED_INTERFACES, {}); EXPECT_THROW( cm_->resource_manager_->make_controller_reference_interfaces_available( @@ -518,17 +693,30 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) // Set ControllerManager into Debug-Mode output to have detailed output on updating controllers cm_->get_logger().set_level(rclcpp::Logger::Level::Debug); + // Before starting check that the internal counters are set to zero + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 0u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 0u); + ASSERT_EQ(diff_drive_controller->internal_counter, 0u); + ASSERT_EQ(diff_drive_controller_two->internal_counter, 0u); + ASSERT_EQ(position_tracking_controller->internal_counter, 0u); + ASSERT_EQ(sensor_fusion_controller->internal_counter, 0u); + ASSERT_EQ(odom_publisher_controller->internal_counter, 0u); + ASSERT_EQ(robot_localization_controller->internal_counter, 0u); + // activate controllers - CONTROLLERS HAVE TO ADDED REVERSE EXECUTION ORDER // (otherwise, interface will be missing) ActivateAndCheckController( pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_CLAIMED_INTERFACES, 1u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 1u); ActivateAndCheckController( pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 1u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 1u); ASSERT_EQ(pid_left_wheel_controller->internal_counter, 3u); // Diff-Drive Controller claims the reference interfaces of PID controllers ActivateAndCheckController( diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 1u); + ASSERT_EQ(diff_drive_controller->internal_counter, 1u); ASSERT_EQ(pid_right_wheel_controller->internal_counter, 3u); ASSERT_EQ(pid_left_wheel_controller->internal_counter, 5u); @@ -536,6 +724,30 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) ActivateAndCheckController( position_tracking_controller, POSITION_TRACKING_CONTROLLER, POSITION_CONTROLLER_CLAIMED_INTERFACES, 1u); + ASSERT_EQ(position_tracking_controller->internal_counter, 1u); + ASSERT_EQ(diff_drive_controller->internal_counter, 3u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 5u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 7u); + + // Sensor Controller uses exported state interfaces of Diff-Drive Controller and IMU + ActivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 1u); + ASSERT_EQ(sensor_fusion_controller->internal_counter, 1u); + ASSERT_EQ(position_tracking_controller->internal_counter, 3u); + ASSERT_EQ(diff_drive_controller->internal_counter, 5u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 7u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 9u); + + // Robot localization Controller uses exported state interfaces of Diff-Drive Controller + ActivateAndCheckController(robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 1u); + ASSERT_EQ(robot_localization_controller->internal_counter, 1u); + ASSERT_EQ(sensor_fusion_controller->internal_counter, 3u); + ASSERT_EQ(position_tracking_controller->internal_counter, 5u); + ASSERT_EQ(diff_drive_controller->internal_counter, 7u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 9u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 11u); + + // Odometry Publisher Controller uses exported state interfaces of Diff-Drive Controller + ActivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 1u); // 'rot_z' reference interface is not claimed for (const auto & interface : {"diff_drive_controller/rot_z"}) { @@ -543,9 +755,13 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); } - ASSERT_EQ(diff_drive_controller->internal_counter, 3u); - ASSERT_EQ(pid_right_wheel_controller->internal_counter, 5u); - ASSERT_EQ(pid_left_wheel_controller->internal_counter, 7u); + ASSERT_EQ(odom_publisher_controller->internal_counter, 1u); + ASSERT_EQ(robot_localization_controller->internal_counter, 3u); + ASSERT_EQ(sensor_fusion_controller->internal_counter, 5u); + ASSERT_EQ(position_tracking_controller->internal_counter, 7u); + ASSERT_EQ(diff_drive_controller->internal_counter, 9u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 11u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 13u); // update controllers std::vector reference = {32.0, 128.0}; @@ -558,25 +774,43 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) position_tracking_controller->external_commands_for_testing_[0] = reference[0]; position_tracking_controller->external_commands_for_testing_[1] = reference[1]; position_tracking_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(position_tracking_controller->internal_counter, 2u); + ASSERT_EQ(position_tracking_controller->internal_counter, 8u); ASSERT_EQ(diff_drive_controller->reference_interfaces_[0], reference[0]); // position_controller ASSERT_EQ(diff_drive_controller->reference_interfaces_[1], reference[1]); // is pass-through // update 'Diff Drive' Controller diff_drive_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(diff_drive_controller->internal_counter, 4u); + ASSERT_EQ(diff_drive_controller->internal_counter, 10u); // default reference values are 0.0 - they should be changed now EXP_LEFT_WHEEL_REF = chained_ctrl_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE); // 32-0 EXP_RIGHT_WHEEL_REF = chained_ctrl_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE); // 128-0 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); + // run the update cycles of the robot localization and odom publisher controller + sensor_fusion_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(sensor_fusion_controller->internal_counter, 6u); + robot_localization_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(robot_localization_controller->internal_counter, 4u); + odom_publisher_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(odom_publisher_controller->internal_counter, 2u); + EXP_STATE_ODOM_X = + chained_estimate_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE); // 32-0 / dt + EXP_STATE_ODOM_Y = + chained_estimate_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE); // 128-0 / dt + ASSERT_EQ(robot_localization_controller->get_state_interface_data().size(), 3u); + ASSERT_EQ(robot_localization_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); + ASSERT_EQ(robot_localization_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); + ASSERT_EQ(odom_publisher_controller->get_state_interface_data().size(), 2u); + ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X); + ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y); + // update PID controllers that are writing to hardware pid_left_wheel_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(pid_left_wheel_controller->internal_counter, 8u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 14u); pid_right_wheel_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(pid_right_wheel_controller->internal_counter, 6u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 12u); // update hardware ('read' is sufficient for test hardware) cm_->resource_manager_->read(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); @@ -588,6 +822,9 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_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); + // 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); // 128 - 0 EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE); @@ -595,8 +832,14 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers) 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(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); + // 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); // update all controllers at once and see that all have expected values --> also checks the order // of controller execution @@ -630,6 +873,18 @@ TEST_P( cm_->add_controller( pid_right_wheel_controller, PID_RIGHT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); CheckIfControllersAreAddedCorrectly(); @@ -652,6 +907,7 @@ TEST_P( EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); // DiffDrive (preceding) controller is activated --> PID controller in chained mode ActivateAndCheckController( @@ -659,6 +915,7 @@ TEST_P( EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); // PositionController is activated --> all following controller in chained mode ActivateAndCheckController( @@ -667,35 +924,153 @@ TEST_P( EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_TRUE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + for (const auto & interface : {"diff_drive_controller/vel_x", "diff_drive_controller/vel_y"}) + { + EXPECT_TRUE(cm_->resource_manager_->command_interface_exists(interface)); + EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); + EXPECT_TRUE(cm_->resource_manager_->command_interface_is_claimed(interface)); + } + for (const auto & interface : {"diff_drive_controller/odom_x", "diff_drive_controller/odom_y"}) + { + EXPECT_TRUE(cm_->resource_manager_->state_interface_exists(interface)); + EXPECT_TRUE(cm_->resource_manager_->state_interface_is_available(interface)); + } + + // Sensor fusion Controller uses exported state interfaces of Diff-Drive Controller and IMU + ActivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 1u); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_TRUE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + + // Robot localization Controller uses exported state interfaces of sensor fusion Controller + ActivateAndCheckController(robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 1u); + + // Odometry Publisher Controller uses exported state interfaces of Diff-Drive Controller + ActivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 1u); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_TRUE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + ASSERT_EQ(robot_localization_controller->internal_counter, 3u); + ASSERT_EQ(odom_publisher_controller->internal_counter, 1u); UpdateAllControllerAndCheck({32.0, 128.0}, 2u); UpdateAllControllerAndCheck({1024.0, 4096.0}, 3u); // Test switch 'from chained mode' when controllers are deactivated - // PositionController is deactivated --> DiffDrive controller is not in chained mode anymore + // PositionController is deactivated --> DiffDrive controller still continues in chained mode + // As the DiffDriveController is in chained mode, right now we tend to also deactivate + // the other controllers that rely on the DiffDriveController exported interfaces DeactivateAndCheckController( position_tracking_controller, POSITION_TRACKING_CONTROLLER, - POSITION_CONTROLLER_CLAIMED_INTERFACES, 4u, true); + POSITION_CONTROLLER_CLAIMED_INTERFACES, 10u, true); EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + // SensorFusionController continues to stay in the chained mode as it is still using the state + // interfaces + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); - // DiffDrive (preceding) controller is activated --> PID controller in chained mode + // Deactivate the robot localization controller and see that the sensor fusion controller is still + // active but not in the chained mode DeactivateAndCheckController( - diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 8u, true); + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 8u, true); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the odometry publisher controller + DeactivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 8u, true); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the sensor_fusion controller and see that the diff_drive_controller is still active + // but not in the chained mode + DeactivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 14u, true); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the diff_drive_controller as all it's following controllers that uses it's + // interfaces are deactivated + DeactivateAndCheckController( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 20u, true); EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); // all controllers are deactivated --> chained mode is not changed DeactivateAndCheckController( - pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_CLAIMED_INTERFACES, 14u, true); + pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_CLAIMED_INTERFACES, 26u, true); DeactivateAndCheckController( - pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 14u, true); + pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 26u, true); EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); } TEST_P( @@ -719,6 +1094,18 @@ TEST_P( cm_->add_controller( pid_right_wheel_controller, PID_RIGHT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); CheckIfControllersAreAddedCorrectly(); @@ -732,6 +1119,7 @@ TEST_P( EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); // Test Case 1: Trying to activate a preceding controller when following controller // is not activated --> return error (If STRICT); Preceding controller is still inactive. @@ -752,6 +1140,17 @@ TEST_P( // Check if the controller activated (Should not be activated) ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + + ActivateController( + SENSOR_FUSION_CONTROLLER, expected.at(test_param.strictness).return_type, + std::future_status::ready); + // Check if the controller activated (Should not be activated) + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); // Test Case 2: Try to activate a preceding controller the same time when trying to // deactivate a following controller (using switch_controller function) @@ -765,11 +1164,11 @@ TEST_P( ActivateAndCheckController( pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 1u); - // Attempt to activate a preceding controller (diff-drive controller) + // Attempt to activate a preceding controller (diff-drive controller + remaining) // while trying to deactivate a following controller switch_test_controllers( - {DIFF_DRIVE_CONTROLLER}, {PID_RIGHT_WHEEL}, test_param.strictness, - expected.at(test_param.strictness).future_status, + {DIFF_DRIVE_CONTROLLER, ODOM_PUBLISHER_CONTROLLER, SENSOR_FUSION_CONTROLLER}, {PID_RIGHT_WHEEL}, + test_param.strictness, expected.at(test_param.strictness).future_status, expected.at(test_param.strictness).return_type); // Preceding controller should stay deactivated and following controller @@ -781,6 +1180,11 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); // Check if the controllers are not in chained mode ASSERT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); @@ -885,6 +1289,18 @@ TEST_P( cm_->add_controller( pid_right_wheel_controller, PID_RIGHT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); CheckIfControllersAreAddedCorrectly(); @@ -901,17 +1317,69 @@ TEST_P( pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 1u); ActivateAndCheckController( diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 1u); + ActivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 1u); + ActivateAndCheckController(robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 1u); + ActivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 1u); + ActivateAndCheckController( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + POSITION_CONTROLLER_CLAIMED_INTERFACES, 1u); - // Verify that the other preceding controller is deactivated (diff_drive_controller_two) + // Verify that the other preceding controller is deactivated (diff_drive_controller_two) and other + // depending controllers are active EXPECT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller_two->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller_two->get_state().id()); + + // Deactivate position_tracking_controller and activate position_tracking_controller_two + switch_test_controllers( + {POSITION_TRACKING_CONTROLLER_TWO}, {POSITION_TRACKING_CONTROLLER}, test_param.strictness, + std::future_status::timeout, controller_interface::return_type::OK); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller_two->get_state().id()); + + // Now deactivate the position_tracking_controller_two and it should be in inactive state + switch_test_controllers( + {}, {POSITION_TRACKING_CONTROLLER_TWO}, test_param.strictness, std::future_status::timeout, + controller_interface::return_type::OK); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller_two->get_state().id()); + + // Activate it again and deactivate it others to see if we can deactivate it in a group + switch_test_controllers( + {POSITION_TRACKING_CONTROLLER_TWO}, {}, test_param.strictness, std::future_status::timeout, + controller_interface::return_type::OK); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller_two->get_state().id()); // Deactivate the first preceding controller (diff_drive_controller) and // activate the other preceding controller (diff_drive_controller_two) switch_test_controllers( - {DIFF_DRIVE_CONTROLLER_TWO}, {DIFF_DRIVE_CONTROLLER}, test_param.strictness, - std::future_status::timeout, controller_interface::return_type::OK); + {DIFF_DRIVE_CONTROLLER_TWO}, + {POSITION_TRACKING_CONTROLLER_TWO, DIFF_DRIVE_CONTROLLER, SENSOR_FUSION_CONTROLLER, + ROBOT_LOCALIZATION_CONTROLLER, ODOM_PUBLISHER_CONTROLLER}, + test_param.strictness, std::future_status::timeout, controller_interface::return_type::OK); // Following controllers should stay active EXPECT_EQ( @@ -924,6 +1392,55 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller_two->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller_two->get_state().id()); + + // Activate all the controllers again in group and deactivate the diff_drive_controller_two + switch_test_controllers( + {POSITION_TRACKING_CONTROLLER_TWO, DIFF_DRIVE_CONTROLLER, SENSOR_FUSION_CONTROLLER, + ROBOT_LOCALIZATION_CONTROLLER, ODOM_PUBLISHER_CONTROLLER}, + {DIFF_DRIVE_CONTROLLER_TWO}, test_param.strictness, std::future_status::timeout, + controller_interface::return_type::OK); + // Following controllers should stay active + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_TRUE(diff_drive_controller->is_in_chained_mode()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + diff_drive_controller_two->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + // This is false, because it only uses the state interfaces and exposes state interfaces + EXPECT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller_two->get_state().id()); } TEST_P( @@ -947,6 +1464,18 @@ TEST_P( cm_->add_controller( pid_right_wheel_controller, PID_RIGHT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); CheckIfControllersAreAddedCorrectly(); @@ -960,6 +1489,7 @@ TEST_P( EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); // Activate following controllers ActivateAndCheckController( @@ -982,11 +1512,28 @@ TEST_P( // Verify preceding controller (diff_drive_controller) is inactive EXPECT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); // Attempt to deactivate inactive controller (diff_drive_controller) DeactivateController( DIFF_DRIVE_CONTROLLER, expected.at(test_param.strictness).return_type, std::future_status::ready); + DeactivateController( + SENSOR_FUSION_CONTROLLER, expected.at(test_param.strictness).return_type, + std::future_status::ready); + DeactivateController( + ODOM_PUBLISHER_CONTROLLER, expected.at(test_param.strictness).return_type, + std::future_status::ready); + DeactivateController( + ROBOT_LOCALIZATION_CONTROLLER, expected.at(test_param.strictness).return_type, + std::future_status::ready); // Check to see preceding controller (diff_drive_controller) is still inactive and // following controllers (pid_left_wheel_controller) (pid_left_wheel_controller) are still active @@ -996,6 +1543,14 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); // Test Case 6: following controller is deactivated but preceding controller will be activated // --> return error; controllers stay in the same state @@ -1098,6 +1653,261 @@ TEST_P( position_tracking_controller->get_state().id()); } +TEST_P( + TestControllerChainingWithControllerManager, + test_chained_controllers_deactivation_switching_error_handling) +{ + SetupControllers(); + + // add all controllers - CONTROLLERS HAVE TO ADDED IN EXECUTION ORDER + cm_->add_controller( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller_two, DIFF_DRIVE_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_left_wheel_controller, PID_LEFT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_right_wheel_controller, PID_RIGHT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + + CheckIfControllersAreAddedCorrectly(); + + ConfigureAndCheckControllers(); + // Set ControllerManager into Debug-Mode output to have detailed output on updating controllers + cm_->get_logger().set_level(rclcpp::Logger::Level::Debug); + rclcpp::get_logger("ControllerManager::utils").set_level(rclcpp::Logger::Level::Debug); + + // at beginning controllers are not in chained mode + EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + + // Activate the following controller and the preceding controllers + ActivateAndCheckController( + pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_CLAIMED_INTERFACES, 1u); + ActivateAndCheckController( + pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 1u); + ActivateAndCheckController( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 1u); + ActivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 1u); + ActivateAndCheckController(robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 1u); + ActivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 1u); + ActivateAndCheckController( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + POSITION_CONTROLLER_CLAIMED_INTERFACES, 1u); + + // check once active that they are in chained mode + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + + // Verify that initially all of them are in active state + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller->get_state().id()); + + // There is different error and timeout behavior depending on strictness + static std::unordered_map expected = { + {controller_manager_msgs::srv::SwitchController::Request::STRICT, + {controller_interface::return_type::ERROR, std::future_status::ready, + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE}}, + {controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT, + {controller_interface::return_type::OK, std::future_status::ready, + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE}}}; + + // Test switch 'from chained mode' when controllers are deactivated and possible combination of + // disabling controllers that use reference/state interfaces of the other controller. This is + // important to check that deactivation is not trigger irrespective of the type + // (reference/state) interface that is shared among the other controllers + + // PositionController is deactivated --> DiffDrive controller still continues in chained mode + // As the DiffDriveController is in chained mode, right now we tend to also deactivate + // the other controllers that rely on the DiffDriveController expected interfaces + DeactivateAndCheckController( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + POSITION_CONTROLLER_CLAIMED_INTERFACES, 2u, true); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(diff_drive_controller->is_in_chained_mode()); + EXPECT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + // SensorFusionController continues to stay in the chained mode as it is still using the state + // interfaces + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); + + // DiffDrive (preceding) controller is activated --> PID controller in chained mod + // Let's try to deactivate the diff_drive_control, it should fail as there are still other + // controllers that use it's resources + DeactivateController( + DIFF_DRIVE_CONTROLLER, expected.at(test_param.strictness).return_type, + expected.at(test_param.strictness).future_status); + check_after_de_activate( + diff_drive_controller, DIFF_DRIVE_CLAIMED_INTERFACES, 0u, + controller_interface::return_type::ERROR, true, true); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + EXPECT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); + + // Trying to deactivate the sensor fusion controller, however, it won't be deactivated as the + // robot localization controller is still active + DeactivateAndCheckController( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 0u, true, + expected.at(test_param.strictness).return_type, + expected.at(test_param.strictness).future_status); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + EXPECT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the robot localization controller and see that the sensor fusion controller is still + // active but not in the chained mode + DeactivateAndCheckController( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 0u); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the sensor_fusion controller and this should be successful as there are no other + // controllers using it's interfaces + DeactivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 0u); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the odometry publisher controller and now the diff_drive should continue active but + // not in chained mode + DeactivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 0u); + EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); + + // Deactivate the diff_drive_controller as all it's following controllers that uses it's + // interfaces are deactivated + DeactivateAndCheckController( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 0u, true); + EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + + // all controllers are deactivated --> chained mode is not changed + DeactivateAndCheckController( + pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_CLAIMED_INTERFACES, 0u, true); + DeactivateAndCheckController( + pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 0u, true); + EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, sensor_fusion_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + odom_publisher_controller->get_state().id()); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + robot_localization_controller->get_state().id()); +} + TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order) { SetupControllers(); @@ -1106,6 +1916,9 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add cm_->add_controller( pid_left_wheel_controller, PID_LEFT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); cm_->add_controller( pid_right_wheel_controller, PID_RIGHT_WHEEL, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); @@ -1118,17 +1931,27 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add cm_->add_controller( diff_drive_controller_two, DIFF_DRIVE_CONTROLLER_TWO, test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); CheckIfControllersAreAddedCorrectly(); ConfigureAndCheckControllers(); - SetToChainedModeAndMakeReferenceInterfacesAvailable( - pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_REFERENCE_INTERFACES); - SetToChainedModeAndMakeReferenceInterfacesAvailable( - pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_REFERENCE_INTERFACES); - SetToChainedModeAndMakeReferenceInterfacesAvailable( - diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + pid_left_wheel_controller, PID_LEFT_WHEEL, {}, PID_LEFT_WHEEL_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + pid_right_wheel_controller, PID_RIGHT_WHEEL, {}, PID_RIGHT_WHEEL_REFERENCE_INTERFACES); + SetToChainedModeAndMakeInterfacesAvailable( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_STATE_INTERFACES, + DIFF_DRIVE_REFERENCE_INTERFACES); EXPECT_THROW( cm_->resource_manager_->make_controller_reference_interfaces_available( @@ -1156,6 +1979,9 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add ActivateAndCheckController( position_tracking_controller, POSITION_TRACKING_CONTROLLER, POSITION_CONTROLLER_CLAIMED_INTERFACES, 1u); + ActivateAndCheckController(sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, {}, 1u); + ActivateAndCheckController(robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, {}, 1u); + ActivateAndCheckController(odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, {}, 1u); // 'rot_z' reference interface is not claimed for (const auto & interface : {"diff_drive_controller/rot_z"}) { @@ -1163,13 +1989,17 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); } - ASSERT_EQ(diff_drive_controller->internal_counter, 3u); - ASSERT_EQ(pid_right_wheel_controller->internal_counter, 5u); - ASSERT_EQ(pid_left_wheel_controller->internal_counter, 7u); + ASSERT_EQ(diff_drive_controller->internal_counter, 9u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 11u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 13u); // update controllers std::vector reference = {32.0, 128.0}; + sensor_fusion_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + robot_localization_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + odom_publisher_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + // update 'Position Tracking' controller for (auto & value : diff_drive_controller->reference_interfaces_) { @@ -1178,14 +2008,14 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add position_tracking_controller->external_commands_for_testing_[0] = reference[0]; position_tracking_controller->external_commands_for_testing_[1] = reference[1]; position_tracking_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(position_tracking_controller->internal_counter, 2u); + ASSERT_EQ(position_tracking_controller->internal_counter, 8u); ASSERT_EQ(diff_drive_controller->reference_interfaces_[0], reference[0]); // position_controller ASSERT_EQ(diff_drive_controller->reference_interfaces_[1], reference[1]); // is pass-through // update 'Diff Drive' Controller diff_drive_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(diff_drive_controller->internal_counter, 4u); + ASSERT_EQ(diff_drive_controller->internal_counter, 10u); // default reference values are 0.0 - they should be changed now EXP_LEFT_WHEEL_REF = chained_ctrl_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE); // 32-0 EXP_RIGHT_WHEEL_REF = chained_ctrl_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE); // 128-0 @@ -1194,9 +2024,9 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add // update PID controllers that are writing to hardware pid_left_wheel_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(pid_left_wheel_controller->internal_counter, 8u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 14u); pid_right_wheel_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - ASSERT_EQ(pid_right_wheel_controller->internal_counter, 6u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 12u); // update hardware ('read' is sufficient for test hardware) cm_->resource_manager_->read(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 6cc2a09a43..b1db90e009 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.12.0 (2024-07-01) +------------------- + 4.11.0 (2024-05-14) ------------------- diff --git a/controller_manager_msgs/msg/ControllerState.msg b/controller_manager_msgs/msg/ControllerState.msg index 3b8e032541..65d773bddc 100644 --- a/controller_manager_msgs/msg/ControllerState.msg +++ b/controller_manager_msgs/msg/ControllerState.msg @@ -6,5 +6,6 @@ string[] required_command_interfaces # command interfaces required by con string[] required_state_interfaces # state interfaces required by controller bool is_chainable # specifies whether or not controller can export references for a controller chain bool is_chained # specifies whether or not controller's exported references are claimed by another controller +string[] exported_state_interfaces # state interfaces to be exported (only applicable if is_chainable is true) string[] reference_interfaces # references to be exported (only applicable if is_chainable is true) ChainConnection[] chain_connections # specifies list of controllers and their exported references that the controller is chained to diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index ddd840154e..387064ca59 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.11.0 + 4.12.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/doc/Doxyfile b/doc/Doxyfile deleted file mode 100644 index d05c75a0b6..0000000000 --- a/doc/Doxyfile +++ /dev/null @@ -1,2579 +0,0 @@ -# Doxyfile 1.8.17 - -# This file describes the settings to be used by the documentation system -# doxygen (www.doxygen.org) for a project. -# -# All text after a double hash (##) is considered a comment and is placed in -# front of the TAG it is preceding. -# -# All text after a single hash (#) is considered a comment and will be ignored. -# The format is: -# TAG = value [value, ...] -# For lists, items can also be appended using: -# TAG += value [value, ...] -# Values that contain spaces should be placed between quotes (\" \"). - -#--------------------------------------------------------------------------- -# Project related configuration options -#--------------------------------------------------------------------------- - -# This tag specifies the encoding used for all characters in the configuration -# file that follow. The default is UTF-8 which is also the encoding used for all -# text before the first occurrence of this tag. Doxygen uses libiconv (or the -# iconv built into libc) for the transcoding. See -# https://www.gnu.org/software/libiconv/ for the list of possible encodings. -# The default value is: UTF-8. - -DOXYFILE_ENCODING = UTF-8 - -# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by -# double-quotes, unless you are using Doxywizard) that should identify the -# project for which the documentation is generated. This name is used in the -# title of most generated pages and in a few other places. -# The default value is: My Project. - -PROJECT_NAME = "ROS2 Control" - -# The PROJECT_NUMBER tag can be used to enter a project or revision number. This -# could be handy for archiving the generated documentation or if some version -# control system is used. - -PROJECT_NUMBER = - -# Using the PROJECT_BRIEF tag one can provide an optional one line description -# for a project that appears at the top of each page and should give viewer a -# quick idea about the purpose of the project. Keep the description short. - -PROJECT_BRIEF = - -# With the PROJECT_LOGO tag one can specify a logo or an icon that is included -# in the documentation. The maximum height of the logo should not exceed 55 -# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy -# the logo to the output directory. - -PROJECT_LOGO = - -# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path -# into which the generated documentation will be written. If a relative path is -# entered, it will be relative to the location where doxygen was started. If -# left blank the current directory will be used. - -OUTPUT_DIRECTORY = doc/_build/ - -# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- -# directories (in 2 levels) under the output directory of each output format and -# will distribute the generated files over these directories. Enabling this -# option can be useful when feeding doxygen a huge amount of source files, where -# putting all generated files in the same directory would otherwise causes -# performance problems for the file system. -# The default value is: NO. - -CREATE_SUBDIRS = NO - -# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII -# characters to appear in the names of generated files. If set to NO, non-ASCII -# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode -# U+3044. -# The default value is: NO. - -ALLOW_UNICODE_NAMES = NO - -# The OUTPUT_LANGUAGE tag is used to specify the language in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all constant output in the proper language. -# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, -# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), -# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, -# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), -# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, -# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, -# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, -# Ukrainian and Vietnamese. -# The default value is: English. - -OUTPUT_LANGUAGE = English - -# The OUTPUT_TEXT_DIRECTION tag is used to specify the direction in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all generated output in the proper direction. -# Possible values are: None, LTR, RTL and Context. -# The default value is: None. - -OUTPUT_TEXT_DIRECTION = None - -# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member -# descriptions after the members that are listed in the file and class -# documentation (similar to Javadoc). Set to NO to disable this. -# The default value is: YES. - -BRIEF_MEMBER_DESC = YES - -# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief -# description of a member or function before the detailed description -# -# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the -# brief descriptions will be completely suppressed. -# The default value is: YES. - -REPEAT_BRIEF = YES - -# This tag implements a quasi-intelligent brief description abbreviator that is -# used to form the text in various listings. Each string in this list, if found -# as the leading text of the brief description, will be stripped from the text -# and the result, after processing the whole list, is used as the annotated -# text. Otherwise, the brief description is used as-is. If left blank, the -# following values are used ($name is automatically replaced with the name of -# the entity):The $name class, The $name widget, The $name file, is, provides, -# specifies, contains, represents, a, an and the. - -ABBREVIATE_BRIEF = "The $name class" \ - "The $name widget" \ - "The $name file" \ - is \ - provides \ - specifies \ - contains \ - represents \ - a \ - an \ - the - -# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then -# doxygen will generate a detailed section even if there is only a brief -# description. -# The default value is: NO. - -ALWAYS_DETAILED_SEC = NO - -# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all -# inherited members of a class in the documentation of that class as if those -# members were ordinary class members. Constructors, destructors and assignment -# operators of the base classes will not be shown. -# The default value is: NO. - -INLINE_INHERITED_MEMB = NO - -# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path -# before files name in the file list and in the header files. If set to NO the -# shortest path that makes the file name unique will be used -# The default value is: YES. - -FULL_PATH_NAMES = YES - -# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. -# Stripping is only done if one of the specified strings matches the left-hand -# part of the path. The tag can be used to show relative paths in the file list. -# If left blank the directory from which doxygen is run is used as the path to -# strip. -# -# Note that you can specify absolute paths here, but also relative paths, which -# will be relative from the directory where doxygen is started. -# This tag requires that the tag FULL_PATH_NAMES is set to YES. - -STRIP_FROM_PATH = - -# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the -# path mentioned in the documentation of a class, which tells the reader which -# header file to include in order to use a class. If left blank only the name of -# the header file containing the class definition is used. Otherwise one should -# specify the list of include paths that are normally passed to the compiler -# using the -I flag. - -STRIP_FROM_INC_PATH = - -# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but -# less readable) file names. This can be useful is your file systems doesn't -# support long names like on DOS, Mac, or CD-ROM. -# The default value is: NO. - -SHORT_NAMES = NO - -# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the -# first line (until the first dot) of a Javadoc-style comment as the brief -# description. If set to NO, the Javadoc-style will behave just like regular Qt- -# style comments (thus requiring an explicit @brief command for a brief -# description.) -# The default value is: NO. - -JAVADOC_AUTOBRIEF = NO - -# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line -# such as -# /*************** -# as being the beginning of a Javadoc-style comment "banner". If set to NO, the -# Javadoc-style will behave just like regular comments and it will not be -# interpreted by doxygen. -# The default value is: NO. - -JAVADOC_BANNER = NO - -# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first -# line (until the first dot) of a Qt-style comment as the brief description. If -# set to NO, the Qt-style will behave just like regular Qt-style comments (thus -# requiring an explicit \brief command for a brief description.) -# The default value is: NO. - -QT_AUTOBRIEF = NO - -# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a -# multi-line C++ special comment block (i.e. a block of //! or /// comments) as -# a brief description. This used to be the default behavior. The new default is -# to treat a multi-line C++ comment block as a detailed description. Set this -# tag to YES if you prefer the old behavior instead. -# -# Note that setting this tag to YES also means that rational rose comments are -# not recognized any more. -# The default value is: NO. - -MULTILINE_CPP_IS_BRIEF = NO - -# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the -# documentation from any documented member that it re-implements. -# The default value is: YES. - -INHERIT_DOCS = YES - -# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new -# page for each member. If set to NO, the documentation of a member will be part -# of the file/class/namespace that contains it. -# The default value is: NO. - -SEPARATE_MEMBER_PAGES = NO - -# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen -# uses this value to replace tabs by spaces in code fragments. -# Minimum value: 1, maximum value: 16, default value: 4. - -TAB_SIZE = 4 - -# This tag can be used to specify a number of aliases that act as commands in -# the documentation. An alias has the form: -# name=value -# For example adding -# "sideeffect=@par Side Effects:\n" -# will allow you to put the command \sideeffect (or @sideeffect) in the -# documentation, which will result in a user-defined paragraph with heading -# "Side Effects:". You can put \n's in the value part of an alias to insert -# newlines (in the resulting output). You can put ^^ in the value part of an -# alias to insert a newline as if a physical newline was in the original file. -# When you need a literal { or } or , in the value part of an alias you have to -# escape them by means of a backslash (\), this can lead to conflicts with the -# commands \{ and \} for these it is advised to use the version @{ and @} or use -# a double escape (\\{ and \\}) - -ALIASES = - -# This tag can be used to specify a number of word-keyword mappings (TCL only). -# A mapping has the form "name=value". For example adding "class=itcl::class" -# will allow you to use the command class in the itcl::class meaning. - -TCL_SUBST = - -# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources -# only. Doxygen will then generate output that is more tailored for C. For -# instance, some of the names that are used will be different. The list of all -# members will be omitted, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_FOR_C = NO - -# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or -# Python sources only. Doxygen will then generate output that is more tailored -# for that language. For instance, namespaces will be presented as packages, -# qualified scopes will look different, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_JAVA = NO - -# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran -# sources. Doxygen will then generate output that is tailored for Fortran. -# The default value is: NO. - -OPTIMIZE_FOR_FORTRAN = NO - -# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL -# sources. Doxygen will then generate output that is tailored for VHDL. -# The default value is: NO. - -OPTIMIZE_OUTPUT_VHDL = NO - -# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice -# sources only. Doxygen will then generate output that is more tailored for that -# language. For instance, namespaces will be presented as modules, types will be -# separated into more groups, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_SLICE = NO - -# Doxygen selects the parser to use depending on the extension of the files it -# parses. With this tag you can assign which parser to use for a given -# extension. Doxygen has a built-in mapping, but you can override or extend it -# using this tag. The format is ext=language, where ext is a file extension, and -# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, -# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, -# Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: -# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser -# tries to guess whether the code is fixed or free formatted code, this is the -# default for Fortran type files), VHDL, tcl. For instance to make doxygen treat -# .inc files as Fortran files (default is PHP), and .f files as C (default is -# Fortran), use: inc=Fortran f=C. -# -# Note: For files without extension you can use no_extension as a placeholder. -# -# Note that for custom extensions you also need to set FILE_PATTERNS otherwise -# the files are not read by doxygen. - -EXTENSION_MAPPING = - -# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments -# according to the Markdown format, which allows for more readable -# documentation. See https://daringfireball.net/projects/markdown/ for details. -# The output of markdown processing is further processed by doxygen, so you can -# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in -# case of backward compatibilities issues. -# The default value is: YES. - -MARKDOWN_SUPPORT = YES - -# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up -# to that level are automatically included in the table of contents, even if -# they do not have an id attribute. -# Note: This feature currently applies only to Markdown headings. -# Minimum value: 0, maximum value: 99, default value: 5. -# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. - -TOC_INCLUDE_HEADINGS = 5 - -# When enabled doxygen tries to link words that correspond to documented -# classes, or namespaces to their corresponding documentation. Such a link can -# be prevented in individual cases by putting a % sign in front of the word or -# globally by setting AUTOLINK_SUPPORT to NO. -# The default value is: YES. - -AUTOLINK_SUPPORT = YES - -# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want -# to include (a tag file for) the STL sources as input, then you should set this -# tag to YES in order to let doxygen match functions declarations and -# definitions whose arguments contain STL classes (e.g. func(std::string); -# versus func(std::string) {}). This also make the inheritance and collaboration -# diagrams that involve STL classes more complete and accurate. -# The default value is: NO. - -BUILTIN_STL_SUPPORT = NO - -# If you use Microsoft's C++/CLI language, you should set this option to YES to -# enable parsing support. -# The default value is: NO. - -CPP_CLI_SUPPORT = NO - -# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: -# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen -# will parse them like normal C++ but will assume all classes use public instead -# of private inheritance when no explicit protection keyword is present. -# The default value is: NO. - -SIP_SUPPORT = NO - -# For Microsoft's IDL there are propget and propput attributes to indicate -# getter and setter methods for a property. Setting this option to YES will make -# doxygen to replace the get and set methods by a property in the documentation. -# This will only work if the methods are indeed getting or setting a simple -# type. If this is not the case, or you want to show the methods anyway, you -# should set this option to NO. -# The default value is: YES. - -IDL_PROPERTY_SUPPORT = YES - -# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC -# tag is set to YES then doxygen will reuse the documentation of the first -# member in the group (if any) for the other members of the group. By default -# all members of a group must be documented explicitly. -# The default value is: NO. - -DISTRIBUTE_GROUP_DOC = NO - -# If one adds a struct or class to a group and this option is enabled, then also -# any nested class or struct is added to the same group. By default this option -# is disabled and one has to add nested compounds explicitly via \ingroup. -# The default value is: NO. - -GROUP_NESTED_COMPOUNDS = NO - -# Set the SUBGROUPING tag to YES to allow class member groups of the same type -# (for instance a group of public functions) to be put as a subgroup of that -# type (e.g. under the Public Functions section). Set it to NO to prevent -# subgrouping. Alternatively, this can be done per class using the -# \nosubgrouping command. -# The default value is: YES. - -SUBGROUPING = YES - -# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions -# are shown inside the group in which they are included (e.g. using \ingroup) -# instead of on a separate page (for HTML and Man pages) or section (for LaTeX -# and RTF). -# -# Note that this feature does not work in combination with -# SEPARATE_MEMBER_PAGES. -# The default value is: NO. - -INLINE_GROUPED_CLASSES = NO - -# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions -# with only public data fields or simple typedef fields will be shown inline in -# the documentation of the scope in which they are defined (i.e. file, -# namespace, or group documentation), provided this scope is documented. If set -# to NO, structs, classes, and unions are shown on a separate page (for HTML and -# Man pages) or section (for LaTeX and RTF). -# The default value is: NO. - -INLINE_SIMPLE_STRUCTS = NO - -# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or -# enum is documented as struct, union, or enum with the name of the typedef. So -# typedef struct TypeS {} TypeT, will appear in the documentation as a struct -# with name TypeT. When disabled the typedef will appear as a member of a file, -# namespace, or class. And the struct will be named TypeS. This can typically be -# useful for C code in case the coding convention dictates that all compound -# types are typedef'ed and only the typedef is referenced, never the tag name. -# The default value is: NO. - -TYPEDEF_HIDES_STRUCT = NO - -# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This -# cache is used to resolve symbols given their name and scope. Since this can be -# an expensive process and often the same symbol appears multiple times in the -# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small -# doxygen will become slower. If the cache is too large, memory is wasted. The -# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range -# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 -# symbols. At the end of a run doxygen will report the cache usage and suggest -# the optimal cache size from a speed point of view. -# Minimum value: 0, maximum value: 9, default value: 0. - -LOOKUP_CACHE_SIZE = 0 - -#--------------------------------------------------------------------------- -# Build related configuration options -#--------------------------------------------------------------------------- - -# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in -# documentation are documented, even if no documentation was available. Private -# class members and static file members will be hidden unless the -# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. -# Note: This will also disable the warnings about undocumented members that are -# normally produced when WARNINGS is set to YES. -# The default value is: NO. - -EXTRACT_ALL = NO - -# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will -# be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIVATE = NO - -# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual -# methods of a class will be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIV_VIRTUAL = NO - -# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal -# scope will be included in the documentation. -# The default value is: NO. - -EXTRACT_PACKAGE = NO - -# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be -# included in the documentation. -# The default value is: NO. - -EXTRACT_STATIC = NO - -# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined -# locally in source files will be included in the documentation. If set to NO, -# only classes defined in header files are included. Does not have any effect -# for Java sources. -# The default value is: YES. - -EXTRACT_LOCAL_CLASSES = YES - -# This flag is only useful for Objective-C code. If set to YES, local methods, -# which are defined in the implementation section but not in the interface are -# included in the documentation. If set to NO, only methods in the interface are -# included. -# The default value is: NO. - -EXTRACT_LOCAL_METHODS = NO - -# If this flag is set to YES, the members of anonymous namespaces will be -# extracted and appear in the documentation as a namespace called -# 'anonymous_namespace{file}', where file will be replaced with the base name of -# the file that contains the anonymous namespace. By default anonymous namespace -# are hidden. -# The default value is: NO. - -EXTRACT_ANON_NSPACES = NO - -# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all -# undocumented members inside documented classes or files. If set to NO these -# members will be included in the various overviews, but no documentation -# section is generated. This option has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_MEMBERS = NO - -# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all -# undocumented classes that are normally visible in the class hierarchy. If set -# to NO, these classes will be included in the various overviews. This option -# has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_CLASSES = NO - -# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# declarations. If set to NO, these declarations will be included in the -# documentation. -# The default value is: NO. - -HIDE_FRIEND_COMPOUNDS = NO - -# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any -# documentation blocks found inside the body of a function. If set to NO, these -# blocks will be appended to the function's detailed documentation block. -# The default value is: NO. - -HIDE_IN_BODY_DOCS = NO - -# The INTERNAL_DOCS tag determines if documentation that is typed after a -# \internal command is included. If the tag is set to NO then the documentation -# will be excluded. Set it to YES to include the internal documentation. -# The default value is: NO. - -INTERNAL_DOCS = NO - -# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file -# names in lower-case letters. If set to YES, upper-case letters are also -# allowed. This is useful if you have classes or files whose names only differ -# in case and if your file system supports case sensitive file names. Windows -# (including Cygwin) ands Mac users are advised to set this option to NO. -# The default value is: system dependent. - -CASE_SENSE_NAMES = YES - -# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with -# their full class and namespace scopes in the documentation. If set to YES, the -# scope will be hidden. -# The default value is: NO. - -HIDE_SCOPE_NAMES = NO - -# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will -# append additional text to a page's title, such as Class Reference. If set to -# YES the compound reference will be hidden. -# The default value is: NO. - -HIDE_COMPOUND_REFERENCE= NO - -# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of -# the files that are included by a file in the documentation of that file. -# The default value is: YES. - -SHOW_INCLUDE_FILES = YES - -# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each -# grouped member an include statement to the documentation, telling the reader -# which file to include in order to use the member. -# The default value is: NO. - -SHOW_GROUPED_MEMB_INC = NO - -# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include -# files with double quotes in the documentation rather than with sharp brackets. -# The default value is: NO. - -FORCE_LOCAL_INCLUDES = NO - -# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the -# documentation for inline members. -# The default value is: YES. - -INLINE_INFO = YES - -# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the -# (detailed) documentation of file and class members alphabetically by member -# name. If set to NO, the members will appear in declaration order. -# The default value is: YES. - -SORT_MEMBER_DOCS = YES - -# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief -# descriptions of file, namespace and class members alphabetically by member -# name. If set to NO, the members will appear in declaration order. Note that -# this will also influence the order of the classes in the class list. -# The default value is: NO. - -SORT_BRIEF_DOCS = NO - -# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the -# (brief and detailed) documentation of class members so that constructors and -# destructors are listed first. If set to NO the constructors will appear in the -# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. -# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief -# member documentation. -# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting -# detailed member documentation. -# The default value is: NO. - -SORT_MEMBERS_CTORS_1ST = NO - -# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy -# of group names into alphabetical order. If set to NO the group names will -# appear in their defined order. -# The default value is: NO. - -SORT_GROUP_NAMES = NO - -# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by -# fully-qualified names, including namespaces. If set to NO, the class list will -# be sorted only by class name, not including the namespace part. -# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. -# Note: This option applies only to the class list, not to the alphabetical -# list. -# The default value is: NO. - -SORT_BY_SCOPE_NAME = NO - -# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper -# type resolution of all parameters of a function it will reject a match between -# the prototype and the implementation of a member function even if there is -# only one candidate or it is obvious which candidate to choose by doing a -# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still -# accept a match between prototype and implementation in such cases. -# The default value is: NO. - -STRICT_PROTO_MATCHING = NO - -# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo -# list. This list is created by putting \todo commands in the documentation. -# The default value is: YES. - -GENERATE_TODOLIST = YES - -# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test -# list. This list is created by putting \test commands in the documentation. -# The default value is: YES. - -GENERATE_TESTLIST = YES - -# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug -# list. This list is created by putting \bug commands in the documentation. -# The default value is: YES. - -GENERATE_BUGLIST = YES - -# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) -# the deprecated list. This list is created by putting \deprecated commands in -# the documentation. -# The default value is: YES. - -GENERATE_DEPRECATEDLIST= YES - -# The ENABLED_SECTIONS tag can be used to enable conditional documentation -# sections, marked by \if ... \endif and \cond -# ... \endcond blocks. - -ENABLED_SECTIONS = - -# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the -# initial value of a variable or macro / define can have for it to appear in the -# documentation. If the initializer consists of more lines than specified here -# it will be hidden. Use a value of 0 to hide initializers completely. The -# appearance of the value of individual variables and macros / defines can be -# controlled using \showinitializer or \hideinitializer command in the -# documentation regardless of this setting. -# Minimum value: 0, maximum value: 10000, default value: 30. - -MAX_INITIALIZER_LINES = 30 - -# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at -# the bottom of the documentation of classes and structs. If set to YES, the -# list will mention the files that were used to generate the documentation. -# The default value is: YES. - -SHOW_USED_FILES = YES - -# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This -# will remove the Files entry from the Quick Index and from the Folder Tree View -# (if specified). -# The default value is: YES. - -SHOW_FILES = YES - -# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces -# page. This will remove the Namespaces entry from the Quick Index and from the -# Folder Tree View (if specified). -# The default value is: YES. - -SHOW_NAMESPACES = YES - -# The FILE_VERSION_FILTER tag can be used to specify a program or script that -# doxygen should invoke to get the current version for each file (typically from -# the version control system). Doxygen will invoke the program by executing (via -# popen()) the command command input-file, where command is the value of the -# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided -# by doxygen. Whatever the program writes to standard output is used as the file -# version. For an example see the documentation. - -FILE_VERSION_FILTER = - -# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed -# by doxygen. The layout file controls the global structure of the generated -# output files in an output format independent way. To create the layout file -# that represents doxygen's defaults, run doxygen with the -l option. You can -# optionally specify a file name after the option, if omitted DoxygenLayout.xml -# will be used as the name of the layout file. -# -# Note that if you run doxygen from a directory containing a file called -# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE -# tag is left empty. - -LAYOUT_FILE = - -# The CITE_BIB_FILES tag can be used to specify one or more bib files containing -# the reference definitions. This must be a list of .bib files. The .bib -# extension is automatically appended if omitted. This requires the bibtex tool -# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. -# For LaTeX the style of the bibliography can be controlled using -# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the -# search path. See also \cite for info how to create references. - -CITE_BIB_FILES = - -#--------------------------------------------------------------------------- -# Configuration options related to warning and progress messages -#--------------------------------------------------------------------------- - -# The QUIET tag can be used to turn on/off the messages that are generated to -# standard output by doxygen. If QUIET is set to YES this implies that the -# messages are off. -# The default value is: NO. - -QUIET = NO - -# The WARNINGS tag can be used to turn on/off the warning messages that are -# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES -# this implies that the warnings are on. -# -# Tip: Turn warnings on while writing the documentation. -# The default value is: YES. - -WARNINGS = YES - -# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate -# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag -# will automatically be disabled. -# The default value is: YES. - -WARN_IF_UNDOCUMENTED = YES - -# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for -# potential errors in the documentation, such as not documenting some parameters -# in a documented function, or documenting parameters that don't exist or using -# markup commands wrongly. -# The default value is: YES. - -WARN_IF_DOC_ERROR = YES - -# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that -# are documented, but have no documentation for their parameters or return -# value. If set to NO, doxygen will only warn about wrong or incomplete -# parameter documentation, but not about the absence of documentation. If -# EXTRACT_ALL is set to YES then this flag will automatically be disabled. -# The default value is: NO. - -WARN_NO_PARAMDOC = NO - -# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when -# a warning is encountered. -# The default value is: NO. - -WARN_AS_ERROR = NO - -# The WARN_FORMAT tag determines the format of the warning messages that doxygen -# can produce. The string should contain the $file, $line, and $text tags, which -# will be replaced by the file and line number from which the warning originated -# and the warning text. Optionally the format may contain $version, which will -# be replaced by the version of the file (if it could be obtained via -# FILE_VERSION_FILTER) -# The default value is: $file:$line: $text. - -WARN_FORMAT = "$file:$line: $text" - -# The WARN_LOGFILE tag can be used to specify a file to which warning and error -# messages should be written. If left blank the output is written to standard -# error (stderr). - -WARN_LOGFILE = - -#--------------------------------------------------------------------------- -# Configuration options related to the input files -#--------------------------------------------------------------------------- - -# The INPUT tag is used to specify the files and/or directories that contain -# documented source files. You may enter file names like myfile.cpp or -# directories like /usr/src/myproject. Separate the files or directories with -# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING -# Note: If this tag is empty the current directory is searched. - -INPUT = README.md . - -# This tag can be used to specify the character encoding of the source files -# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses -# libiconv (or the iconv built into libc) for the transcoding. See the libiconv -# documentation (see: https://www.gnu.org/software/libiconv/) for the list of -# possible encodings. -# The default value is: UTF-8. - -INPUT_ENCODING = UTF-8 - -# If the value of the INPUT tag contains directories, you can use the -# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and -# *.h) to filter out the source-files in the directories. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# read by doxygen. -# -# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, -# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, -# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, -# *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment), -# *.doc (to be provided as doxygen C comment), *.txt (to be provided as doxygen -# C comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f, *.for, *.tcl, *.vhd, -# *.vhdl, *.ucf, *.qsf and *.ice. - -FILE_PATTERNS = *.c \ - *.cc \ - *.cxx \ - *.cpp \ - *.c++ \ - *.java \ - *.ii \ - *.ixx \ - *.ipp \ - *.i++ \ - *.inl \ - *.idl \ - *.ddl \ - *.odl \ - *.h \ - *.hh \ - *.hxx \ - *.hpp \ - *.h++ \ - *.cs \ - *.d \ - *.php \ - *.php4 \ - *.php5 \ - *.phtml \ - *.inc \ - *.m \ - *.markdown \ - *.md \ - *.mm \ - *.dox \ - *.doc \ - *.txt \ - *.py \ - *.pyw \ - *.f90 \ - *.f95 \ - *.f03 \ - *.f08 \ - *.f \ - *.for \ - *.tcl \ - *.vhd \ - *.vhdl \ - *.ucf \ - *.qsf \ - *.ice - -# The RECURSIVE tag can be used to specify whether or not subdirectories should -# be searched for input files as well. -# The default value is: NO. - -RECURSIVE = YES - -# The EXCLUDE tag can be used to specify files and/or directories that should be -# excluded from the INPUT source files. This way you can easily exclude a -# subdirectory from a directory tree whose root is specified with the INPUT tag. -# -# Note that relative paths are relative to the directory from which doxygen is -# run. - -EXCLUDE = - -# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or -# directories that are symbolic links (a Unix file system feature) are excluded -# from the input. -# The default value is: NO. - -EXCLUDE_SYMLINKS = NO - -# If the value of the INPUT tag contains directories, you can use the -# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude -# certain files from those directories. -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories for example use the pattern */test/* - -EXCLUDE_PATTERNS = - -# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names -# (namespaces, classes, functions, etc.) that should be excluded from the -# output. The symbol name can be a fully qualified name, a word, or if the -# wildcard * is used, a substring. Examples: ANamespace, AClass, -# AClass::ANamespace, ANamespace::*Test -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories use the pattern */test/* - -EXCLUDE_SYMBOLS = - -# The EXAMPLE_PATH tag can be used to specify one or more files or directories -# that contain example code fragments that are included (see the \include -# command). - -EXAMPLE_PATH = - -# If the value of the EXAMPLE_PATH tag contains directories, you can use the -# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and -# *.h) to filter out the source-files in the directories. If left blank all -# files are included. - -EXAMPLE_PATTERNS = * - -# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be -# searched for input files to be used with the \include or \dontinclude commands -# irrespective of the value of the RECURSIVE tag. -# The default value is: NO. - -EXAMPLE_RECURSIVE = NO - -# The IMAGE_PATH tag can be used to specify one or more files or directories -# that contain images that are to be included in the documentation (see the -# \image command). - -IMAGE_PATH = - -# The INPUT_FILTER tag can be used to specify a program that doxygen should -# invoke to filter for each input file. Doxygen will invoke the filter program -# by executing (via popen()) the command: -# -# -# -# where is the value of the INPUT_FILTER tag, and is the -# name of an input file. Doxygen will then use the output that the filter -# program writes to standard output. If FILTER_PATTERNS is specified, this tag -# will be ignored. -# -# Note that the filter must not add or remove lines; it is applied before the -# code is scanned, but not when the output code is generated. If lines are added -# or removed, the anchors will not be placed correctly. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# properly processed by doxygen. - -INPUT_FILTER = - -# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern -# basis. Doxygen will compare the file name with each pattern and apply the -# filter if there is a match. The filters are a list of the form: pattern=filter -# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how -# filters are used. If the FILTER_PATTERNS tag is empty or if none of the -# patterns match the file name, INPUT_FILTER is applied. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# properly processed by doxygen. - -FILTER_PATTERNS = - -# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using -# INPUT_FILTER) will also be used to filter the input files that are used for -# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). -# The default value is: NO. - -FILTER_SOURCE_FILES = NO - -# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file -# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and -# it is also possible to disable source filtering for a specific pattern using -# *.ext= (so without naming a filter). -# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. - -FILTER_SOURCE_PATTERNS = - -# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that -# is part of the input, its contents will be placed on the main page -# (index.html). This can be useful if you have a project on for instance GitHub -# and want to reuse the introduction page also for the doxygen output. - -USE_MDFILE_AS_MAINPAGE = README.md - -#--------------------------------------------------------------------------- -# Configuration options related to source browsing -#--------------------------------------------------------------------------- - -# If the SOURCE_BROWSER tag is set to YES then a list of source files will be -# generated. Documented entities will be cross-referenced with these sources. -# -# Note: To get rid of all source code in the generated output, make sure that -# also VERBATIM_HEADERS is set to NO. -# The default value is: NO. - -SOURCE_BROWSER = NO - -# Setting the INLINE_SOURCES tag to YES will include the body of functions, -# classes and enums directly into the documentation. -# The default value is: NO. - -INLINE_SOURCES = NO - -# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any -# special comment blocks from generated source code fragments. Normal C, C++ and -# Fortran comments will always remain visible. -# The default value is: YES. - -STRIP_CODE_COMMENTS = YES - -# If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# entity all documented functions referencing it will be listed. -# The default value is: NO. - -REFERENCED_BY_RELATION = NO - -# If the REFERENCES_RELATION tag is set to YES then for each documented function -# all documented entities called/used by that function will be listed. -# The default value is: NO. - -REFERENCES_RELATION = NO - -# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set -# to YES then the hyperlinks from functions in REFERENCES_RELATION and -# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will -# link to the documentation. -# The default value is: YES. - -REFERENCES_LINK_SOURCE = YES - -# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the -# source code will show a tooltip with additional information such as prototype, -# brief description and links to the definition and documentation. Since this -# will make the HTML file larger and loading of large files a bit slower, you -# can opt to disable this feature. -# The default value is: YES. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -SOURCE_TOOLTIPS = YES - -# If the USE_HTAGS tag is set to YES then the references to source code will -# point to the HTML generated by the htags(1) tool instead of doxygen built-in -# source browser. The htags tool is part of GNU's global source tagging system -# (see https://www.gnu.org/software/global/global.html). You will need version -# 4.8.6 or higher. -# -# To use it do the following: -# - Install the latest version of global -# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file -# - Make sure the INPUT points to the root of the source tree -# - Run doxygen as normal -# -# Doxygen will invoke htags (and that will in turn invoke gtags), so these -# tools must be available from the command line (i.e. in the search path). -# -# The result: instead of the source browser generated by doxygen, the links to -# source code will now point to the output of htags. -# The default value is: NO. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -USE_HTAGS = NO - -# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a -# verbatim copy of the header file for each class for which an include is -# specified. Set to NO to disable this. -# See also: Section \class. -# The default value is: YES. - -VERBATIM_HEADERS = YES - -# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the -# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the -# cost of reduced performance. This can be particularly helpful with template -# rich C++ code for which doxygen's built-in parser lacks the necessary type -# information. -# Note: The availability of this option depends on whether or not doxygen was -# generated with the -Duse_libclang=ON option for CMake. -# The default value is: NO. - -CLANG_ASSISTED_PARSING = NO - -# If clang assisted parsing is enabled you can provide the compiler with command -# line options that you would normally use when invoking the compiler. Note that -# the include paths will already be set by doxygen for the files and directories -# specified with INPUT and INCLUDE_PATH. -# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. - -CLANG_OPTIONS = - -# If clang assisted parsing is enabled you can provide the clang parser with the -# path to the compilation database (see: -# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) used when the files -# were built. This is equivalent to specifying the "-p" option to a clang tool, -# such as clang-check. These options will then be passed to the parser. -# Note: The availability of this option depends on whether or not doxygen was -# generated with the -Duse_libclang=ON option for CMake. - -CLANG_DATABASE_PATH = - -#--------------------------------------------------------------------------- -# Configuration options related to the alphabetical class index -#--------------------------------------------------------------------------- - -# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all -# compounds will be generated. Enable this if the project contains a lot of -# classes, structs, unions or interfaces. -# The default value is: YES. - -ALPHABETICAL_INDEX = YES - -# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in -# which the alphabetical index list will be split. -# Minimum value: 1, maximum value: 20, default value: 5. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -COLS_IN_ALPHA_INDEX = 5 - -# In case all classes in a project start with a common prefix, all classes will -# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag -# can be used to specify a prefix (or a list of prefixes) that should be ignored -# while generating the index headers. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -IGNORE_PREFIX = - -#--------------------------------------------------------------------------- -# Configuration options related to the HTML output -#--------------------------------------------------------------------------- - -# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output -# The default value is: YES. - -GENERATE_HTML = YES - -# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a -# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of -# it. -# The default directory is: html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_OUTPUT = html - -# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each -# generated HTML page (for example: .htm, .php, .asp). -# The default value is: .html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FILE_EXTENSION = .html - -# The HTML_HEADER tag can be used to specify a user-defined HTML header file for -# each generated HTML page. If the tag is left blank doxygen will generate a -# standard header. -# -# To get valid HTML the header file that includes any scripts and style sheets -# that doxygen needs, which is dependent on the configuration options used (e.g. -# the setting GENERATE_TREEVIEW). It is highly recommended to start with a -# default header using -# doxygen -w html new_header.html new_footer.html new_stylesheet.css -# YourConfigFile -# and then modify the file new_header.html. See also section "Doxygen usage" -# for information on how to generate the default header that doxygen normally -# uses. -# Note: The header is subject to change so you typically have to regenerate the -# default header when upgrading to a newer version of doxygen. For a description -# of the possible markers and block names see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_HEADER = - -# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each -# generated HTML page. If the tag is left blank doxygen will generate a standard -# footer. See HTML_HEADER for more information on how to generate a default -# footer and what special commands can be used inside the footer. See also -# section "Doxygen usage" for information on how to generate the default footer -# that doxygen normally uses. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FOOTER = - -# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style -# sheet that is used by each HTML page. It can be used to fine-tune the look of -# the HTML output. If left blank doxygen will generate a default style sheet. -# See also section "Doxygen usage" for information on how to generate the style -# sheet that doxygen normally uses. -# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as -# it is more robust and this tag (HTML_STYLESHEET) will in the future become -# obsolete. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_STYLESHEET = - -# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined -# cascading style sheets that are included after the standard style sheets -# created by doxygen. Using this option one can overrule certain style aspects. -# This is preferred over using HTML_STYLESHEET since it does not replace the -# standard style sheet and is therefore more robust against future updates. -# Doxygen will copy the style sheet files to the output directory. -# Note: The order of the extra style sheet files is of importance (e.g. the last -# style sheet in the list overrules the setting of the previous ones in the -# list). For an example see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_STYLESHEET = - -# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or -# other source files which should be copied to the HTML output directory. Note -# that these files will be copied to the base HTML output directory. Use the -# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these -# files. In the HTML_STYLESHEET file, use the file name only. Also note that the -# files will be copied as-is; there are no commands or markers available. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_FILES = - -# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen -# will adjust the colors in the style sheet and background images according to -# this color. Hue is specified as an angle on a colorwheel, see -# https://en.wikipedia.org/wiki/Hue for more information. For instance the value -# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 -# purple, and 360 is red again. -# Minimum value: 0, maximum value: 359, default value: 220. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_HUE = 220 - -# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors -# in the HTML output. For a value of 0 the output will use grayscales only. A -# value of 255 will produce the most vivid colors. -# Minimum value: 0, maximum value: 255, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_SAT = 100 - -# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the -# luminance component of the colors in the HTML output. Values below 100 -# gradually make the output lighter, whereas values above 100 make the output -# darker. The value divided by 100 is the actual gamma applied, so 80 represents -# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not -# change the gamma. -# Minimum value: 40, maximum value: 240, default value: 80. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_GAMMA = 80 - -# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML -# page will contain the date and time when the page was generated. Setting this -# to YES can help to show when doxygen was last run and thus if the -# documentation is up to date. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_TIMESTAMP = NO - -# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML -# documentation will contain a main index with vertical navigation menus that -# are dynamically created via JavaScript. If disabled, the navigation index will -# consists of multiple levels of tabs that are statically embedded in every HTML -# page. Disable this option to support browsers that do not have JavaScript, -# like the Qt help browser. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_MENUS = YES - -# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML -# documentation will contain sections that can be hidden and shown after the -# page has loaded. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_SECTIONS = NO - -# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries -# shown in the various tree structured indices initially; the user can expand -# and collapse entries dynamically later on. Doxygen will expand the tree to -# such a level that at most the specified number of entries are visible (unless -# a fully collapsed tree already exceeds this amount). So setting the number of -# entries 1 will produce a full collapsed tree by default. 0 is a special value -# representing an infinite number of entries and will result in a full expanded -# tree by default. -# Minimum value: 0, maximum value: 9999, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_INDEX_NUM_ENTRIES = 100 - -# If the GENERATE_DOCSET tag is set to YES, additional index files will be -# generated that can be used as input for Apple's Xcode 3 integrated development -# environment (see: https://developer.apple.com/xcode/), introduced with OSX -# 10.5 (Leopard). To create a documentation set, doxygen will generate a -# Makefile in the HTML output directory. Running make will produce the docset in -# that directory and running make install will install the docset in -# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at -# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy -# genXcode/_index.html for more information. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_DOCSET = NO - -# This tag determines the name of the docset feed. A documentation feed provides -# an umbrella under which multiple documentation sets from a single provider -# (such as a company or product suite) can be grouped. -# The default value is: Doxygen generated docs. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_FEEDNAME = "Doxygen generated docs" - -# This tag specifies a string that should uniquely identify the documentation -# set bundle. This should be a reverse domain-name style string, e.g. -# com.mycompany.MyDocSet. Doxygen will append .docset to the name. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_BUNDLE_ID = org.doxygen.Project - -# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify -# the documentation publisher. This should be a reverse domain-name style -# string, e.g. com.mycompany.MyDocSet.documentation. -# The default value is: org.doxygen.Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_ID = org.doxygen.Publisher - -# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. -# The default value is: Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_NAME = Publisher - -# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three -# additional HTML index files: index.hhp, index.hhc, and index.hhk. The -# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop -# (see: https://www.microsoft.com/en-us/download/details.aspx?id=21138) on -# Windows. -# -# The HTML Help Workshop contains a compiler that can convert all HTML output -# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML -# files are now used as the Windows 98 help format, and will replace the old -# Windows help format (.hlp) on all Windows platforms in the future. Compressed -# HTML files also contain an index, a table of contents, and you can search for -# words in the documentation. The HTML workshop also contains a viewer for -# compressed HTML files. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_HTMLHELP = NO - -# The CHM_FILE tag can be used to specify the file name of the resulting .chm -# file. You can add a path in front of the file if the result should not be -# written to the html output directory. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_FILE = - -# The HHC_LOCATION tag can be used to specify the location (absolute path -# including file name) of the HTML help compiler (hhc.exe). If non-empty, -# doxygen will try to run the HTML help compiler on the generated index.hhp. -# The file has to be specified with full path. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -HHC_LOCATION = - -# The GENERATE_CHI flag controls if a separate .chi index file is generated -# (YES) or that it should be included in the master .chm file (NO). -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -GENERATE_CHI = NO - -# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) -# and project file content. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_INDEX_ENCODING = - -# The BINARY_TOC flag controls whether a binary table of contents is generated -# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it -# enables the Previous and Next buttons. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -BINARY_TOC = NO - -# The TOC_EXPAND flag can be set to YES to add extra items for group members to -# the table of contents of the HTML help documentation and to the tree view. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -TOC_EXPAND = NO - -# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and -# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that -# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help -# (.qch) of the generated HTML documentation. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_QHP = NO - -# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify -# the file name of the resulting .qch file. The path specified is relative to -# the HTML output folder. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QCH_FILE = - -# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help -# Project output. For more information please see Qt Help Project / Namespace -# (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_NAMESPACE = org.doxygen.Project - -# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt -# Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual- -# folders). -# The default value is: doc. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_VIRTUAL_FOLDER = doc - -# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom -# filter to add. For more information please see Qt Help Project / Custom -# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- -# filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_NAME = - -# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the -# custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- -# filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_ATTRS = - -# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this -# project's filter section matches. Qt Help Project / Filter Attributes (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_SECT_FILTER_ATTRS = - -# The QHG_LOCATION tag can be used to specify the location of Qt's -# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the -# generated .qhp file. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHG_LOCATION = - -# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be -# generated, together with the HTML files, they form an Eclipse help plugin. To -# install this plugin and make it available under the help contents menu in -# Eclipse, the contents of the directory containing the HTML and XML files needs -# to be copied into the plugins directory of eclipse. The name of the directory -# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. -# After copying Eclipse needs to be restarted before the help appears. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_ECLIPSEHELP = NO - -# A unique identifier for the Eclipse help plugin. When installing the plugin -# the directory name containing the HTML and XML files should also have this -# name. Each documentation set should have its own identifier. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. - -ECLIPSE_DOC_ID = org.doxygen.Project - -# If you want full control over the layout of the generated HTML pages it might -# be necessary to disable the index and replace it with your own. The -# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top -# of each HTML page. A value of NO enables the index and the value YES disables -# it. Since the tabs in the index contain the same information as the navigation -# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -DISABLE_INDEX = NO - -# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index -# structure should be generated to display hierarchical information. If the tag -# value is set to YES, a side panel will be generated containing a tree-like -# index structure (just like the one that is generated for HTML Help). For this -# to work a browser that supports JavaScript, DHTML, CSS and frames is required -# (i.e. any modern browser). Windows users are probably better off using the -# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can -# further fine-tune the look of the index. As an example, the default style -# sheet generated by doxygen has an example that shows how to put an image at -# the root of the tree instead of the PROJECT_NAME. Since the tree basically has -# the same information as the tab index, you could consider setting -# DISABLE_INDEX to YES when enabling this option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_TREEVIEW = NO - -# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that -# doxygen will group on one line in the generated HTML documentation. -# -# Note that a value of 0 will completely suppress the enum values from appearing -# in the overview section. -# Minimum value: 0, maximum value: 20, default value: 4. -# This tag requires that the tag GENERATE_HTML is set to YES. - -ENUM_VALUES_PER_LINE = 4 - -# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used -# to set the initial width (in pixels) of the frame in which the tree is shown. -# Minimum value: 0, maximum value: 1500, default value: 250. -# This tag requires that the tag GENERATE_HTML is set to YES. - -TREEVIEW_WIDTH = 250 - -# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to -# external symbols imported via tag files in a separate window. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -EXT_LINKS_IN_WINDOW = NO - -# Use this tag to change the font size of LaTeX formulas included as images in -# the HTML documentation. When you change the font size after a successful -# doxygen run you need to manually remove any form_*.png images from the HTML -# output directory to force them to be regenerated. -# Minimum value: 8, maximum value: 50, default value: 10. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_FONTSIZE = 10 - -# Use the FORMULA_TRANSPARENT tag to determine whether or not the images -# generated for formulas are transparent PNGs. Transparent PNGs are not -# supported properly for IE 6.0, but are supported on all modern browsers. -# -# Note that when changing this option you need to delete any form_*.png files in -# the HTML output directory before the changes have effect. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_TRANSPARENT = YES - -# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands -# to create new LaTeX commands to be used in formulas as building blocks. See -# the section "Including formulas" for details. - -FORMULA_MACROFILE = - -# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# https://www.mathjax.org) which uses client side JavaScript for the rendering -# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX -# installed or if you want to formulas look prettier in the HTML output. When -# enabled you may also need to install MathJax separately and configure the path -# to it using the MATHJAX_RELPATH option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -USE_MATHJAX = NO - -# When MathJax is enabled you can set the default output format to be used for -# the MathJax output. See the MathJax site (see: -# http://docs.mathjax.org/en/latest/output.html) for more details. -# Possible values are: HTML-CSS (which is slower, but has the best -# compatibility), NativeMML (i.e. MathML) and SVG. -# The default value is: HTML-CSS. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_FORMAT = HTML-CSS - -# When MathJax is enabled you need to specify the location relative to the HTML -# output directory using the MATHJAX_RELPATH option. The destination directory -# should contain the MathJax.js script. For instance, if the mathjax directory -# is located at the same level as the HTML output directory, then -# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax -# Content Delivery Network so you can quickly see the result without installing -# MathJax. However, it is strongly recommended to install a local copy of -# MathJax from https://www.mathjax.org before deployment. -# The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/ - -# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax -# extension names that should be enabled during MathJax rendering. For example -# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_EXTENSIONS = - -# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces -# of code that will be used on startup of the MathJax code. See the MathJax site -# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an -# example see the documentation. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_CODEFILE = - -# When the SEARCHENGINE tag is enabled doxygen will generate a search box for -# the HTML output. The underlying search engine uses javascript and DHTML and -# should work on any modern browser. Note that when using HTML help -# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) -# there is already a search function so this one should typically be disabled. -# For large projects the javascript based search engine can be slow, then -# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to -# search using the keyboard; to jump to the search box use + S -# (what the is depends on the OS and browser, but it is typically -# , /