From 331da4abd8509482e03c0710a37356e7daf8f7a2 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Sun, 5 Dec 2021 21:29:19 +0900 Subject: [PATCH] feat: add multi_object_tracker package (#74) * release v0.4.0 * remove ROS1 packages temporarily Signed-off-by: mitsudome-r * Revert "remove ROS1 packages temporarily" This reverts commit 4acc04bb2a3b2ef21e687a8d3ba88008fa32846b. Signed-off-by: mitsudome-r * add COLCON_IGNORE to ros1 packages Signed-off-by: mitsudome-r * Rename launch files to launch.xml (#28) * ROS2 Porting: multi_object_tracker (#24) * First pass at node (exclude tracker library) - Rename files to match existing packages - node -> _core - main -> _node - Add publishers and subscribers - Add TF and logging - issue with lookupTransform from tf2::BufferCore doesn't allow for duration specification in foxy bfe938b7971f96b343cdf30e15b7157863804644 * Add the base implementation of the helper class and files - Depends on the unique_id package which has not been release rosdep yet - Point to the correct packages - Add vehicle_tracker class - Missing uuid implementation for the object id creation - Convert bicycle_tracker class - Convert pedestrian_tracker to ROS2 - Add successive_shortest_path library - Changed header file extension to match existing files - Convert data_association to ROS2 - Return type change to resolve -Wreturn-type warning * Add data associator and tracker method calls back into the MultiObjectTracker implementation * Clean up - Align headers - Fix typo - Add back the transform with no duration; see issue - Remove comments * Clean up package.xml and CMakelists * Clean up header order * Remove main file * Fix issues after rebase - Add wait for transform to add duration - Add UUID generation - Add -Werror * Address PR comment: - Reintroduce getUUID method in tracker code * Fix the waitForTransform implementation - Use the synchronous approach to getting the transform using wait_for() * Address PR comments: - Add further comments in CMakelist explaining Eigen library deps - Use durable transient_local QoS for subscriber - Remove second explicit string type decl - Convert buffer and listener to plain objects, move initialization to initialization list - Make generation of random bits more idiomatic - Use indepedent_bit_engine instead of uniform distribution * Address PR comments: - Fix eigen cmake dep * Fix Eigen3 deps - find cmake module * fix duration unit for RCLCPP_*_THROTTLE (#75) Signed-off-by: Takamasa Horibe * Adjust copyright notice on 532 out of 699 source files (#143) * Use quotes for includes where appropriate (#144) * Use quotes for includes where appropriate * Fix lint tests * Make tests pass hopefully * Run uncrustify on the entire Pilot.Auto codebase (#151) * Run uncrustify on the entire Pilot.Auto codebase * Exclude open PRs * adding linters to multi_object_tracker (#177) * [multi_object_tracker] fix bug in calculating timer period (#198) Signed-off-by: mitsudome-r * Replace waitForTransform with lookupTransform in multi_object_tracker (#213) * Ros2 v0.8.0 multi object tracker (#259) * restore file name for v0.8.0 update Signed-off-by: wep21 * fix typos in perception (#862) * Feature/camera lidar perception (#937) * add object splitter Signed-off-by: Yukihiro Saito * add object merger Signed-off-by: Yukihiro Saito * change pkg name Signed-off-by: Yukihiro Saito * cosmetic change Signed-off-by: Yukihiro Saito * add comment Signed-off-by: Yukihiro Saito * remove litter Signed-off-by: Yukihiro Saito * bug fix : debug code Signed-off-by: Yukihiro Saito * enable vehicle to unknown track Signed-off-by: Yukihiro Saito * bug fix * add object position in clustering * :put_litter_in_its_place: * change param * fix name * bug fix * add install * add delay compensation param (#1035) * fix tracking bug and change tracking param (#1036) * fix bug * cut stop noise velocity * update param * support unknown labeled object tracking (#1017) * add data association matrix param * fix typo * apply clang-format-6.0 * set pedestrian model when label is unknown Co-authored-by: Yukihiro Saito * Add missing install of config directory (#1045) Signed-off-by: Kenji Miyake * Revert "restore file name for v0.8.0 update" This reverts commit 5fdf5b179f2395f01672c976920da1f8de8cc33a. * Fix typo Signed-off-by: wep21 * Fix parameter type Signed-off-by: wep21 * Fix missing arg Signed-off-by: wep21 Co-authored-by: Kazuki Miyahara Co-authored-by: Yukihiro Saito Co-authored-by: Taichi Higashide Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix min_area (#347) Signed-off-by: Kosuke Murakami * Rename ROS-related .yaml to .param.yaml (#352) * Rename ROS-related .yaml to .param.yaml Signed-off-by: Kenji Miyake * Remove prefix 'default_' of yaml files Signed-off-by: Kenji Miyake * Rename vehicle_info.yaml to vehicle_info.param.yaml Signed-off-by: Kenji Miyake * Rename diagnostic_aggregator's param files Signed-off-by: Kenji Miyake * Fix overlooked parameters Signed-off-by: Kenji Miyake * Feature/ekf tracker (#1158) (#381) * Feature/ekf tracker (#1158) * change to ekf tracker * visualize covariance * cosmetic change * cosmetic change * change param * add multi model ekf tracker (#1165) * add multi model ekf tracker * cosmetic change * cosmetic change * add iou filter * change correct license * change correct license * cosmetic change * bug fix * cosmetic change * check clockwise * change param * bug fix * cosmetic change * add comment * add enum * cosmetic change * cosmetic change * apply format * apply format * fix config name Signed-off-by: mitsudome-r * [multi_object_tracker] apply ament_uncrustify Signed-off-by: mitsudome-r * [multi_object_tracker] fix lint errors Signed-off-by: mitsudome-r * fix include brackets Signed-off-by: mitsudome-r * fix duration (#445) * fix duration Signed-off-by: Kosuke Murakami * change to from_seconds Signed-off-by: Kosuke Murakami * fix other duration Signed-off-by: Kosuke Murakami * replace -1 with 0 Signed-off-by: Kosuke Murakami * apply ament_lint_common Signed-off-by: Kosuke Murakami * uncrustify Signed-off-by: Kosuke Murakami * add space Signed-off-by: Kosuke Murakami * add another space Signed-off-by: Kosuke Murakami * Fix typo in perception module (#440) * add use_sim-time option (#454) * Remove use_sim_time for set_parameter (#1260) Signed-off-by: wep21 * fix calculation of corners (#1271) (#1273) * fix calculation of corners * reduce calc cost Co-authored-by: Yukihiro Saito Co-authored-by: Yusuke Muramatsu Co-authored-by: Yukihiro Saito * Porting small fix (#1288) * Delete unused code (#1183) * Fix control topic name of closest_velocity_checker.py (#1174) Signed-off-by: Kenji Miyake * Add comments for livox tag (#1188) Signed-off-by: Kenji Miyake * Clear return value (#1193) * Change tracker model of unknown object (#1204) * treat polygon points as relative (#1205) Signed-off-by: Kosuke Murakami * hotfix: reference velocity in consideration of vehicle gear (#1213) * fix reference velocity for vehicle gear * add initialization * revert * add comment * change max area param (#1218) * Fix an identical code for different branches (#1230) * Update livox_tag_filter.launch.xml * Fixup Signed-off-by: Kenji Miyake Co-authored-by: shin <8327162+0x126@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Fumiya Watanabe Co-authored-by: Yukihiro Saito Co-authored-by: Kosuke Murakami Co-authored-by: Hiroki OTA Co-authored-by: tkimura4 Co-authored-by: Kazuki Miyahara Co-authored-by: Kenji Miyake * fix bug (change noise in measurement update) (#1313) * fix bug (change noise in measurement update) * Uncrustify Signed-off-by: wep21 Co-authored-by: Yukihiro Saito * Feature/porting mussp with vendor (#1323) * change to mussp (#1180) * change to mussp * add license * add license * change to solver plugin * fix bug * cosmetic change * modified to follow ROS2 coding style * Use mussp vendor Signed-off-by: wep21 * Fix dependencies in package.xml Signed-off-by: wep21 * Add mussp_vendor into build_depends.repos Signed-off-by: wep21 * Fix lint Signed-off-by: wep21 * Fix typo Signed-off-by: wep21 * Fix typo Signed-off-by: wep21 * Fix lint Signed-off-by: wep21 * Use fork instead of vendor package Signed-off-by: wep21 * Cleanup CMakeLists.txt Signed-off-by: wep21 * Remove comment Signed-off-by: wep21 * Sort package dependencies in alphabetical order Signed-off-by: wep21 Co-authored-by: Yukihiro Saito Co-authored-by: Keisuke Shima * Porting unknown tracker (#1292) * add unknown tracker (#1211) * add unknown tracker * bug fix * fix typo * fix for test Co-authored-by: Yukihiro Saito * Fix/tracking ros2 (#1478) * cosmetic change and fix multi model tracker update bug (#1335) * Fix lint Signed-off-by: wep21 * Fix typo Signed-off-by: wep21 Co-authored-by: Yukihiro Saito * Add missing eigen macro (#1336) (#1477) Signed-off-by: wep21 * Fix parameter file for mot (#1489) Signed-off-by: wep21 * Add pre-commit (#1560) * add pre-commit * add pre-commit-config * add additional settings for private repository * use default pre-commit-config * update pre-commit setting * Ignore whitespace for line breaks in markdown * Update .github/workflows/pre-commit.yml Co-authored-by: Kazuki Miyahara * exclude svg * remove pretty-format-json * add double-quote-string-fixer * consider COLCON_IGNORE file when seaching modified package * format file * pre-commit fixes * Update pre-commit.yml * Update .pre-commit-config.yaml Co-authored-by: Kazuki Miyahara Co-authored-by: pre-commit Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Add markdownlint and prettier (#1661) * Add markdownlint and prettier Signed-off-by: Kenji Miyake * Ignore .param.yaml Signed-off-by: Kenji Miyake * Apply format Signed-off-by: Kenji Miyake * suppress warnings for declare parameters (#1724) * fix for lanelet2_extension * fix for traffic light ssd fine detector * fix for topic_state_monitor * fix for dummy diag publisher * fix for remote cmd converter * fix for vehicle_info_util * fix for multi object tracker * fix for freespace planner * fix for autoware_error_monitor * add Werror for multi object tracker * fix for multi object tracker * add Werror for liraffic light ssd fine detector * add Werror for topic state monitor * add Werror * add Werror * add Werror * add Werror * fix style * Fix -Wunused-parameter (#1836) * Fix -Wunused-parameter Signed-off-by: Kenji Miyake * Fix mistake Signed-off-by: Kenji Miyake * fix spell * Fix lint issues Signed-off-by: Kenji Miyake * Ignore flake8 warnings Signed-off-by: Kenji Miyake Co-authored-by: Hiroki OTA * Fix clang warnings (#1859) * Fix -Wreturn-std-move Signed-off-by: Kenji Miyake * Fix -Wunused-private-field Signed-off-by: Kenji Miyake * Ignore -Wnonportable-include-path for mussp Signed-off-by: Kenji Miyake * Fix -Wunused-const-variable Signed-off-by: Kenji Miyake * Fix "can not be used when making a shared object" Signed-off-by: Kenji Miyake * Feature/porting modify tracker life cycle (#1675) * Modify tracker life cycle (#1462) * add z lpf Signed-off-by: Yukihiro Saito * modify life cycle Signed-off-by: Yukihiro Saito * refactor * apply format * fix typo * add read me * fix typo * change readme * modify readme * fix typo * cosmetic change * cosmetic change * refactor and change removal conditions * cosmetic change * add note * bug fix * change specific alive pattern * format code Co-authored-by: Takamasa Horibe * Apply lint Signed-off-by: wep21 * pre-commit fixes Signed-off-by: wep21 * fix bug Co-authored-by: Yukihiro Saito Co-authored-by: Takamasa Horibe Co-authored-by: tkimura4 * Detection by tracker (#1910) * initial commit * backup * apply format * cosmetic change * implement divided under segmenterd clusters * cosmetic change * bug fix * bug fix * bug fix * modify launch * add debug and bug fix * bug fix * bug fix * add no found tracked object * modify parameters and cmake * bug fix * remove debug info * add readme * modify clustering launch * run pre-commit * cosmetic change * cosmetic change * cosmetic change * apply markdownlint * modify launch * modify for cpplint * modify qos * change int to size_T * bug fix * change perception qos * Update perception/object_recognition/detection/detection_by_tracker/package.xml Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * cosmetic change * cosmetic change * fix launch * Update perception/object_recognition/detection/detection_by_tracker/src/utils.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * modify header include order * change include order * Update perception/object_recognition/detection/detection_by_tracker/src/detection_by_tracker_core.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * change to std::optional * cosmetic change * Update perception/object_recognition/detection/detection_by_tracker/src/detection_by_tracker_core.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * Update perception/object_recognition/detection/detection_by_tracker/src/detection_by_tracker_core.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * bug fix * modify readme Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * Change formatter to clang-format and black (#2332) * Revert "Temporarily comment out pre-commit hooks" This reverts commit 748e9cdb145ce12f8b520bcbd97f5ff899fc28a3. * Replace ament_lint_common with autoware_lint_common Signed-off-by: Kenji Miyake * Remove ament_cmake_uncrustify and ament_clang_format Signed-off-by: Kenji Miyake * Apply Black Signed-off-by: Kenji Miyake * Apply clang-format Signed-off-by: Kenji Miyake * Fix build errors Signed-off-by: Kenji Miyake * Fix for cpplint * Fix include double quotes to angle brackets Signed-off-by: Kenji Miyake * Apply clang-format Signed-off-by: Kenji Miyake * Fix build errors Signed-off-by: Kenji Miyake * Add COLCON_IGNORE (#500) Signed-off-by: Kenji Miyake * Port multi object tracker for autoware_auto_msgs (#526) * backup * backup * backup * add todo author * apply pre-commit * remove COLCON_IGNORE * fix: fix README.md * ci(pre-commit): autofix * Apply suggestions from code review Co-authored-by: mitsudome-r Co-authored-by: Nikolai Morin Co-authored-by: Jilada Eccleston Co-authored-by: Takamasa Horibe Co-authored-by: nik-tier4 <71747268+nik-tier4@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Kazuki Miyahara Co-authored-by: Yukihiro Saito Co-authored-by: Taichi Higashide Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kosuke Murakami Co-authored-by: tkimura4 Co-authored-by: Yusuke Muramatsu Co-authored-by: Keisuke Shima Co-authored-by: shin <8327162+0x126@users.noreply.github.com> Co-authored-by: Fumiya Watanabe Co-authored-by: Hiroki OTA Co-authored-by: Kenji Miyake Co-authored-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../multi_object_tracker/CMakeLists.txt | 70 +++ perception/multi_object_tracker/README.md | 131 ++++++ .../config/data_association_matrix.param.yaml | 52 +++ .../image/multi_object_tracker_overview.svg | 3 + .../image/mussp_evaluation1.png | Bin 0 -> 72714 bytes .../image/mussp_evaluation2.png | Bin 0 -> 81846 bytes .../data_association/data_association.hpp | 62 +++ .../data_association/solver/gnn_solver.hpp | 22 + .../solver/gnn_solver_interface.hpp | 35 ++ .../solver/mu_successive_shortest_path.hpp | 37 ++ .../solver/successive_shortest_path.hpp | 37 ++ .../multi_object_tracker_core.hpp | 79 ++++ .../tracker/model/bicycle_tracker.hpp | 92 ++++ .../tracker/model/big_vehicle_tracker.hpp | 91 ++++ .../model/multiple_vehicle_tracker.hpp | 49 ++ .../tracker/model/normal_vehicle_tracker.hpp | 92 ++++ .../model/pedestrian_and_bicycle_tracker.hpp | 48 ++ .../tracker/model/pedestrian_tracker.hpp | 98 ++++ .../tracker/model/tracker_base.hpp | 93 ++++ .../tracker/model/unknown_tracker.hpp | 77 ++++ .../multi_object_tracker/tracker/tracker.hpp | 31 ++ .../multi_object_tracker/utils/utils.hpp | 87 ++++ .../launch/multi_object_tracker.launch.xml | 17 + perception/multi_object_tracker/package.xml | 32 ++ .../src/data_association/data_association.cpp | 212 +++++++++ .../mu_successive_shortest_path_wrapper.cpp | 41 ++ .../successive_shortest_path.cpp | 370 +++++++++++++++ .../src/multi_object_tracker_core.cpp | 386 ++++++++++++++++ .../src/tracker/model/bicycle_tracker.cpp | 403 +++++++++++++++++ .../src/tracker/model/big_vehicle_tracker.cpp | 421 ++++++++++++++++++ .../model/multiple_vehicle_tracker.cpp | 61 +++ .../tracker/model/normal_vehicle_tracker.cpp | 421 ++++++++++++++++++ .../model/pedestrian_and_bicycle_tracker.cpp | 61 +++ .../src/tracker/model/pedestrian_tracker.cpp | 409 +++++++++++++++++ .../src/tracker/model/tracker_base.cpp | 63 +++ .../src/tracker/model/unknown_tracker.cpp | 298 +++++++++++++ .../multi_object_tracker/src/utils/utils.cpp | 218 +++++++++ 37 files changed, 4699 insertions(+) create mode 100644 perception/multi_object_tracker/CMakeLists.txt create mode 100644 perception/multi_object_tracker/README.md create mode 100644 perception/multi_object_tracker/config/data_association_matrix.param.yaml create mode 100644 perception/multi_object_tracker/image/multi_object_tracker_overview.svg create mode 100644 perception/multi_object_tracker/image/mussp_evaluation1.png create mode 100644 perception/multi_object_tracker/image/mussp_evaluation2.png create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/data_association/data_association.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver_interface.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/mu_successive_shortest_path.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/successive_shortest_path.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/tracker/tracker.hpp create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp create mode 100644 perception/multi_object_tracker/launch/multi_object_tracker.launch.xml create mode 100644 perception/multi_object_tracker/package.xml create mode 100644 perception/multi_object_tracker/src/data_association/data_association.cpp create mode 100644 perception/multi_object_tracker/src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp create mode 100644 perception/multi_object_tracker/src/data_association/successive_shortest_path/successive_shortest_path.cpp create mode 100644 perception/multi_object_tracker/src/multi_object_tracker_core.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/tracker_base.cpp create mode 100644 perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp create mode 100644 perception/multi_object_tracker/src/utils/utils.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt new file mode 100644 index 0000000000000..c944af87e4bc5 --- /dev/null +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -0,0 +1,70 @@ +cmake_minimum_required(VERSION 3.5) +project(multi_object_tracker) + +### Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +# Ignore -Wnonportable-include-path in Clang for mussp +if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-nonportable-include-path) +endif() + +### Find Packages +find_package(ament_cmake_auto REQUIRED) + +### Find Eigen Dependencies +find_package(eigen3_cmake_module REQUIRED) +find_package(Eigen3 REQUIRED) + +### Find dependencies listed in the package.xml +ament_auto_find_build_dependencies() + +# Generate exe file +set(MULTI_OBJECT_TRACKER_SRC + src/multi_object_tracker_core.cpp + src/utils/utils.cpp + src/tracker/model/tracker_base.cpp + src/tracker/model/big_vehicle_tracker.cpp + src/tracker/model/normal_vehicle_tracker.cpp + src/tracker/model/multiple_vehicle_tracker.cpp + src/tracker/model/bicycle_tracker.cpp + src/tracker/model/pedestrian_tracker.cpp + src/tracker/model/pedestrian_and_bicycle_tracker.cpp + src/tracker/model/unknown_tracker.cpp + src/data_association/data_association.cpp +) + +ament_auto_add_library(mu_successive_shortest_path SHARED + src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp +) + +ament_auto_add_library(multi_object_tracker_node SHARED + ${MULTI_OBJECT_TRACKER_SRC} +) + +target_link_libraries(multi_object_tracker_node + mu_successive_shortest_path + Eigen3::Eigen +) + +rclcpp_components_register_node(multi_object_tracker_node + PLUGIN "MultiObjectTracker" + EXECUTABLE multi_object_tracker +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/perception/multi_object_tracker/README.md b/perception/multi_object_tracker/README.md new file mode 100644 index 0000000000000..e6111384f1476 --- /dev/null +++ b/perception/multi_object_tracker/README.md @@ -0,0 +1,131 @@ +# multi_object_tracker + +## Purpose + +The results of the detection are processed by a time series. The main purpose is to give ID and estimate velocity. + +## Inner-workings / Algorithms + +This multi object tracker consists of data association and EKF. + +![multi_object_tracker_overview](image/multi_object_tracker_overview.svg) + +### Data association + +The data association performs maximum score matching, called min cost max flow problem. +In this package, mussp[1] is used as solver. +In addition, when associating observations to tracers, data association have gates such as the area of the object from the BEV, Mahalanobis distance, and maximum distance, depending on the class label. + +### EKF Tracker + +Models for pedestrians, bicycles (motorcycles), cars and unknown are available. +The pedestrian or bicycle tracker is running at the same time as the respective EKF model in order to enable the transition between pedestrian and bicycle tracking. +For big vehicles such as trucks and buses, we have separate models for passenger cars and large vehicles because they are difficult to distinguish from passenger cars and are not stable. Therefore, separate models are prepared for passenger cars and big vehicles, and these models are run at the same time as the respective EKF models to ensure stability. + + + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| --------- | ----------------------------------------------------- | ----------- | +| `~/input` | `autoware_auto_perception_msgs::msg::DetectedObjects` | obstacles | + +### Output + +| Name | Type | Description | +| ---------- | ---------------------------------------------------- | ------------------ | +| `~/output` | `autoware_auto_perception_msgs::msg::TrackedObjects` | modified obstacles | + +## Parameters + + + +### Core Parameters + +| Name | Type | Description | +| --------------------------- | ------ | -------------------------------------------------------------- | +| `can_assign_matrix` | double | Assignment table for data association | +| `max_dist_matrix` | double | Maximum distance table for data association | +| `max_area_matrix` | double | Maximum area table for data association | +| `min_area_matrix` | double | Minimum area table for data association | +| `max_rad_matrix` | double | Maximum angle table for data association | +| `world_frame_id` | double | tracking frame | +| `enable_delay_compensation` | bool | Estimate obstacles at current time considering detection delay | +| `publish_rate` | double | if enable_delay_compensation is true, how many hertz to output | + +## Assumptions / Known limits + + + +## (Optional) Error detection and handling + + + +## (Optional) Performance characterization + +### Evaluation of muSSP + +According to our evaluation, muSSP is faster than normal [SSP](src/data_association/successive_shortest_path) when the matrix size is more than 100. + +Execution time for varying matrix size at 95% sparsity. In real data, the sparsity was often around 95%. +![mussp_evaluation1](image/mussp_evaluation1.png) + +Execution time for varying the sparsity with matrix size 100. +![mussp_evaluation2](image/mussp_evaluation2.png) + +## (Optional) References/External links + +This package makes use of external code. + +| Name | License | Original Repository | +| -------------------------------------------------------------- | ------------------------------------------------------------------- | ------------------------------------ | +| [muSSP](src/data_association/mu_successive_shortest_path/impl) | [Apache 2.0](src/data_association/mu_successive_shortest_path/impl) | | + +[1] C. Wang, Y. Wang, Y. Wang, C.-t. Wu, and G. Yu, “muSSP: Efficient +Min-cost Flow Algorithm for Multi-object Tracking,” NeurIPS, 2019 + +## (Optional) Future extensions / Unimplemented parts + + diff --git a/perception/multi_object_tracker/config/data_association_matrix.param.yaml b/perception/multi_object_tracker/config/data_association_matrix.param.yaml new file mode 100644 index 0000000000000..393bb949d048d --- /dev/null +++ b/perception/multi_object_tracker/config/data_association_matrix.param.yaml @@ -0,0 +1,52 @@ +/**: + ros__parameters: + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 1, 1, 1, 1, 0, 0, 0, 0, #CAR + 1, 1, 1, 1, 0, 0, 0, 0, #TRUCK + 1, 1, 1, 1, 0, 0, 0, 0, #BUS + 0, 0, 0, 0, 1, 1, 1, 0, #BICYCLE + 0, 0, 0, 0, 1, 1, 1, 0, #MOTORBIKE + 0, 0, 0, 0, 1, 1, 1, 0, #PEDESTRIAN + 0, 0, 0, 0, 0, 0, 0, 1] #ANIMAL + max_dist_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN + 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #CAR + 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #BUS + 3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #BICYCLE + 3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #MOTORBIKE + 2.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #PEDESTRIAN + 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] #ANIMAL + max_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN + 12.10, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #CAR + 19.75, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #TRUCK + 32.40, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #BUS + 2.50, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #BICYCLE + 3.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #MOTORBIKE + 2.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00, 10000.00, #PEDESTRIAN + 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00] #ANIMAL + min_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN + 3.600, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #CAR + 6.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #TRUCK + 10.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #BUS + 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #BICYCLE + 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #MOTORBIKE + 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #PEDESTRIAN + 0.500, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #ANIMAL + max_rad_matrix: # If value is greater than pi, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #BUS + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #PEDESTRIAN + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #ANIMAL diff --git a/perception/multi_object_tracker/image/multi_object_tracker_overview.svg b/perception/multi_object_tracker/image/multi_object_tracker_overview.svg new file mode 100644 index 0000000000000..23fc0455db016 --- /dev/null +++ b/perception/multi_object_tracker/image/multi_object_tracker_overview.svg @@ -0,0 +1,3 @@ + + +
Trackers
Tracke...
Observations
Observ...
Match
Match

Data association

Optimization of combination between trackers and observations

Data association...

Update

Tracker

Update...

Update

Tracker

prediction

Update...

Generate

Tracker

Generate...

Check tracker life cycle
Check tracker life cycle

Delete the tracker

Delete the...

Nothing to do

Nothing to...

Send the result

Send the re...
If the tracker
doesn’t match with
any observation in
a certain period
If the tracker...
If the count of
the match for the
tracker is less than
a certain number
If the count of...
Else
Else

Tracker

not matched

Tracker...

Observation

not matched

Observation...
Viewer does not support full SVG 1.1
\ No newline at end of file diff --git a/perception/multi_object_tracker/image/mussp_evaluation1.png b/perception/multi_object_tracker/image/mussp_evaluation1.png new file mode 100644 index 0000000000000000000000000000000000000000..b17b743051808cbb68c40014619a12dc4cfd3788 GIT binary patch literal 72714 zcmd43cRZH;8$RApDMAu=vJ*nGvPUAaCCQe(_ueHdvg5YZV<&{{ot>4H>~x#S-dW%C zy7l?Jet&=e`ugK}o_cQAeZAk;`99C%IL_m|UMnd`UA{zq>C~xHm!%&`D4#lY*8J3| zGw!(O;cwJ~3+drsI1Ue_RdC_Q6W1^Z{(Rl>p_=0p8)HWoJ$s{5Ce}7qMt2+x?2U}9 z9ZYQ;SI*XnoH|8wN?Jlp#Wm^AxVpm)lhWCJQR4VExz4jU&Cu;mpJ)h2(X*DKtqT9u~AmKdIkB3XTM~A@>f?S#pJOcH2lJp{W=Kwkwcxk zhy7IK#k6+}*pG4QkqrF1+#BBn?5EoN9{;~_vCa*V7a<>p7JJQ0Py~TZ`W*P;@z1a~ zTdR!w)w<)I`p^K zBW0jEopix5K_=r%S0ZoEe#FTW^ljGX$jr?A#ERF?UB{K3^Ys1y?UUL*u#rXu^fqq@ z`O*X(v8|WFw(1w60`#7v&ab%&nd9wiFX=smZ=GIJR`QVj!cLESMl$Wnp?7M-^ZP_N zyR|+Ofeb4VcK3@}@mlR{DK0d!lk_1s$?(Q^M00)X-S?H9H7{K;`H2s9*SdBNnLeFv z!mK%na3W8^Eg3$;NkOo%v+tU6;f2*`uXJ(S=(_tg7jE)i>$0@33Erg0cQXVcpCb>Q zcNFl`3o=XiQ5tGB$`^Ll)Fq@wW|TNrB?8d+7*l&RqaY{PAKdkM7qaO+4R;elUO6Y z(bCw2c1^PIR%v=-h#mbxwSku^*p-Dao7?o3o9m&@XS)5(dv;CU+g$hfdPpngvF6cG zt0eL$+NPBr%1=|K>k=V^YdSwe7o(f=n)0@hAxNIytzZ7rD$bxw`qO;*qNadEPizBAY*aV{K?jz{k~_LVIUQ z`K2=R`;()~`JQBet%AnyJ=r(Pzr9XgJ*{=8x^DhG6zMXK*2t5r8qXXwpV~jV(Xj*1 z_sNqdBq0weS{rt}&c8Z6XdYu;a>;YB$w;V?ExJ9TW2Vix*sxgLb26*fR4I4RlqZop zQT|2t)cGWy7Z8)v8*XsQ+6|S9Td^DR!#k}egl&2}P&7lLbjGorCW$(FhGBq+Va05`U4Mt4D-W zp5GC}@~qr>i99zq_hWv3-{O|*+OKorRKogRUdeDq^ih)Bb8PtHtR26W$E&pJypv~U zjAmzNPjVN-j~3}bA0M{|HG*eoQa|qwnoEnxPq(fMh4-3DXW52yDp5aFD@aN)wA<>mF?gDf8gnG4nM8`=MR$3q@!%1sVi0J~Yc(!a99 zFCt=WVDJj=Wc^n&p4QMUbcfz3Ps-fspOw~|adHgeJc;K9-igEJ7!p4n6;Gl3%x_M3 ziYdz~U(uv{FS}Os+`V`{I74uf&gE}yIa!aDHz0Wkb~V6G;Hf@0IR|-YTuMr&3Ugsy zT~A{m;qZ?i&z+oNj{oW&vy@sHjPeBNNpvt!wl+9vU-CcmT7u4f+*L>+Lzy;4rVx@* zUmtOWR+vJTcv|ms2Zv}y(ZjdBrcJ+o(K$FcTrxuv&U&eCT~%NN6RrlelE`sF-!2%Ycu86=cAD9xr;2&K9*#_@YimwV!=?_ zeI`;@-tJCV_-@rZVII?qi2tNB$2lv-*3o{`czxn-Ae7#xw*+5hJkOB z&gxI^H~Y25x8|DUC?KDs0=rpUQ`1#yfO$_+j;Wz?GWJ z4=2y@iIP&{DXFE?x_|Bs=k1tnN!oM@?MvO;zsVCOs3O=nUpXgbRZTP9YrWB_(^`nn zng4L2q+A$%YcZiIbR}Qa>&B2%e0=k!tB3T*=s~h zF828XRn?Zr-S80=L2(VQmClqZ(RKa>{7GD&*1XeVME2i=s=`I%gPzFUVluIuU1w_$ zRU(n2C!V(F&&<;$jJEdUF7 zt@zL)Kj;li9OG{Q-Lm3)*_V)H)8X8Wg%)wg4 zGnDrdB~L20$-;vRC2KmF3R#U%FYgYOkn4ScWMgjfDL1Mx%xdD~ zK|o2#J(-L?e(yjeM^6`3eY<@NztME|JDIL$1CmEVLPJCADs-VR^qR8s^0wM|Z`^)qcKqOGI#>yORZ($qV|O>f=;-L5m6c+M-nBSvhswL)NSkcwOFIVq9Wp&{FQwQO3Jm}HH_&*0)`K2Dx^DV zugxpeo~x&a^0jZK_9#l+Q$_BUEekJM8NT018@?a;-|=z*<|ThyyuPqcA06&{uD3J7 zd4YtlrmdZ!#;VYH^q>96Y|S2pgInNoeb!3yI8}+cM_XeJLl5Cduaj&By~}KoihXx{ zjRKu@M3H=7Y5RkQ!`@JdT5E~`&Um@cWtPCp2$2ByP3a{rQSeO;a=E1B)$rAFK#LsNJ)(4Ec+kf`T1izg}wA zx6>Ecj^W}_AJU%=#F<){`DppfV^{1^$>HEcjYYqiw~JNqjhN2(nlLf^#-Jya>0SNzO3%H$Q{aH)4kG2$ zXAkW&g$WluYI&!cqmr${JXUV^Dv{TQQ&g0?%k0LpA-R5)TiB=KtxR@g=};|aJ=X2T zihD*NnV?4JuK8R_yCD;4$Xl6=*Jku*BG@tXovE3XLzKJemeGEDPnqNyevv3&%;Yk8 z_E=CB4iN>xnwRL`H-MWVA5IC7hCDo*ZBU33BVtG4L)I8DFUeN#j5ABvtqlj*tRYQF z*ig#K@|%^Pmv^VXP7g^V{0`nI&dsxbZ>G}VFA&HFc)y_bYtkor^}7A+DJDDsL1+%O&ap}x>LVN+73Qs)9kRXJ9$P*`J_>-asL)z+a_u}-fV@ChTmxjU z&E#6AvFleQ8^E`&E(CeJYM{AL9(UD}lw6L(@`*+e|%k5AvyY+BL z&^;U3s=1F_TU>>xo(=$fOqqL}JD5GR$a?p#lt+75csRh5dhV|IBdA}1v9kL0xXA$! z)g2$MR5;8L!0FW~aG9`CN6ta_3+e#J3nIxcrSb&RCvNmox!%VY#jSX>6(f6N005Dc zl$4Oq5e1eev9hs6DP+~{H~{wgJ~UL}b1XtgCG@jBnz7dkL;H28K=+xFpn)DrQp{4w zSx<=Y4!$_t-D?S7PZ33t)VZ3S2?HyuP)N}IS&Dnp(TWI)BftD>&2`|Qv4|C_#oo+a zpY|1><9()b7Az^&A`m;3{IXTrd=|`2+;? z0sjpSK4p%%1m*GZ==RFZ#IB;EB3}$2D=X{jM(VLpr4@YS0wLA&(Ncj^DIBAvw@EGm zm<2Ec>7-?&nu(}Yp98rU_UYe)xsXPn4(!dRg{x_3{0Ag=aqGX}kzET&>SkuIp$-%c zvu2t_bs1NZ-?k)MNk$Fv(&{ z&F;;Qg}v$Yz!F(BJC?r%H0piEx3;!s1F}0kEtuFPNxQV@F>tioD%xktjlw^F$=t+} z!n=RLktCuujkE=!K5GtRJfisG01JRM)8OLz(u}0>9FZfyY(G?q=O~Gcj4W+GtV#}h zKBhNbMZ6?aS_$3NFKa*EpMPQQ()OI>xflNm@1jQe>)rUS{lgsXN(##wc)Q5a8)MFoV#vh1< zA7=La-mgwEOAy^HLBea=(_ilq?&rTZx5>Q#0a>aF{^8w+)cJ+mmi25a_orW3$yAJc zV~0-B9;HV&xAwgV2nmNrM{nYb%VZEY>qj~Y0JoeJ5MM0%DnPn&cRH@e=i2ji=@5OH zK{{l&D}H<-@@1cX$N%%#`n&7rNyEc(@yQLlPQKeLVFt+8HE1Km$h0ay@?nV$ADFOi{(M5>2!PC9`%0*dL- z_4OP4mfLQ21G6)a6VXzX0^;HJEwe3h2{Ab&A?MJZeP6iQtj8+2WvO4$)bDsf)qoU4 zK}DrM%JVE=OV8L?@)}lzij;jPdg+J7=5W4~TlM6xc5gfuDubN3>8~omnlbpfGu*Jo zII{F>$GjEXVpgol3Jx=0ubqlTqi>@-(v@>u@<-E<9c?q>Tt6G2Q*UQcztPAOzMWt> z~>=&X`}YNsC<9^WQ3y znX8Vtz_LyRI=0kEYWB^u+vLJjf4E&gjiwJ%N0!RR%1Dc-eRVKk5brJtYA(MY-B+9V zPoa}bCqnI>hJ>$L(viw*E;M3693s}jQK6x*k(hgn6i+(p^=`&Rvv=>D_bzKF`JC&j zDaeJd|FTDk#_n1f)DuKI_~bUGS3EM)pb-7aI8_Z_HM5VERNML~r(A~Bm_*Vp zT9~C}7LTn?<4)gik9xCDiFeEAwqm{6&y{rKPrgX*dA@k;>7+g5^@#o&Rz@_W^S@8z zw<#skLnwG)cIXGoR~QlJ3~OH+#;?=5!;$LJEF-ImL0Yv9dfdxkfKxo?P>Z8dFsu}lBXGyPXj0EA4|l&Gd9y3dAgEVUY0;(>~XNDc>k4uCGxj{UGn8la@CtSsPAp!2|sRdS!|RJ%3+ zN(6M8l#~?li2f11f@b%5vHMWyMoKKSYTRS&E9B@Rl@PHu60bmTQ%!Vvwb?ovEoBup zdX_V+c`F{j%%qr=B+8H?T4JpHTXA1)h;Krh3+h4+=%A2a0ME}Y^k-RGT7u{UBBTvY z+RlW>-4AbuOXX1k1LpUj2D`0KU-a4Q&~@EgH*)lu+_~uc0yrUTWdzTnwDa;_M(i2@)o*9cB8h=qveJsZwzHQ@I=P1wxxim)R z)`v>B6sfXNpkh$}c2kcxeDo6-SXfxpzRw&f%EGO(6_}ee*?H9Wzamv69I+g#q`%5w zaV@cGLtVAQ4D>E(LGOvcztPBJCrIlJac`_uYY`>VE68>!FgM$r8WD0TEk^jZ7Gg;d>*Q#^ib$70_VH9sEFz4IRR4g4wx>1I(VC zf&g@$$sIe2xzKk;sPnN#Q+xzDD#0L$aK<;4S^?1HkmtG-eCSO*2zL3D#a0qs)KRm9^KUxSMKqx)yFk9|4f^-|{z}mT6RY(m=G(*^&+oroP@ao;o ze#O0AO!(~>8My7?6%>1(DJ;+O*+oSmiA;sut$hwq&bzMXIs4Cv8jpi@ zbX}8^_V&(B&d?&lsp6kA$GG3j7WO`fL)eraV9wOzgE=6C0?7(0cW&HO2eAoLqD~3$ zSdCQ@^mZc(KH;8_FNtOe^u({3Btmz}Lla+MwQZj=x>#%npjW3{jWu9p|8dYgd~s}L zVDqEFHzO1xNb~}ISZLU0?RUED2!}c|10afWj%Z`Hl_89+%Kwj`p)2o=$r+^@o@=3y>SXKHzcP)^J_HbXlk6(prHVEhJy}g8J^_RE&>7q5Qf!a{f*Q?dXY?fyjhtt zS6EfmVUp?FvGJ zlPcP3mo&eI;W@&z9>25kfSU7yi5`KHa+Nf=YmNQtW*%Eqii8@~e3r#eR(fyjeU!^6 z=R#vN_`CEuq?gZ>jU01;Iw!VI6qfp6|5U(IakAa_yf0H^--M5TS7I2m-v6HO9j*y8 z6Q?_?K$@AKs`Kl$&-`t#$*iG82yVy+AM^4av!OZgUpZHG=^m|<9f24Mn#WZq1<&Kd zoxQ;V?`BX*Jv=;4L3)(Xn++_@FJleK$+>MgI@_BjwYl$=BINd)o2*3(n2 zU??P3Dy%V8V>1MhP5OrKi;1?Z2?(RQX6h7bhi?=_e(b3(6@salXDkmP+{3n(Rr*?x zjo855WFeXp1P7vBLWfK-Rb-~&)dl?XXMsim zvk{#~wM;QW^PtNZ#JuEWN~n6a6oC~L{Km${h#q2O>^W&m47 z_lJ7`L4dxgR4@cYzSj$>@MB|!P}&itth!pRLMu~?t+>3r4N3n{WI$bqqAk%gxw7N7 z{YRafX#Z;r3$g^bo1_%v{Qksv?hvJIIwU3M?_aHS( zMZiu&T5#p82%|u5B91kI%(Di2MKpa_rOD1%&EJKT&-KT@E60T7#{D)o;dC#&NIuO- zn8Vq0wC2=Q@T?eW{^#`7tx+gHSef09g7J48Uu_pVzUO4?Mm6tjh?iz#C=Kp^r2Clt z@J0=u#9N77PzNC$^uGA5vE-<}@SL3{@{z5pYtUjPlnA81GY}>kFQ?2z0;d}OCQ>G& zZEgeTjB=hTC`*t`Og~|b+bQ7JOtN2*H&8pX3#n$RI2oLE-+|n_@r6|Blnu(sUaKc zvj2Q)w2yXqc0XMGHI#};6rc|iychOrWJni}CSFdm!OGe?Y|8c#$b;_g0ve?JRBsL| z?S7K?cx!5DO+&as))F~Ba5&o1J&pkw_It~HpqrWo8Wok5GOVPS?|GWA`iFP+tVS8o z9g*#ZpR6>oe8y1U|32!APFgEt;!|L`Klm0vpz0*k^0v!p>yinms21aLS;n!uRI81-x@dlpdh9i) zXbOVB$Lu$BhZeV>xd`CG6t(4Qy0u$zxsfJDCbHdgD;`)r94;UQ5YnIsLRagg~Q*LQ&?yMF37 z#FTeDCsC4NRJ)zw>OPxhes=h3C? zi(g#{60y{lWAlvjqSyEEQK2!bBD+4l`E#AK6tS|>)~ZGDA4T~Y5!<(r8)(AVL2uWN z0vfogxxEXH03)Ht>t1std9QQF3p@;BL=scCaeYmdw$woM6cE#hy>=&jQ|PXFhA2U> zZb8#M^2@Me09On-bGk!;=G!me*Su&{O$CWbNEB-DVx-fZuh#>2$kw&)WW{&$T{45v zjCS!|tOOxT@>Lc9!f8YA z0#sC0CCeP64@ne+P3UCeivz+a2gwf$_tI(%1N6R`a+{WD0CfYfU+%Tf0}Sbs1#)+{ zHv>dMCnA#F!&~?70Bbhgl2WlJkZqjQtL{ppkgB=K*QVRA zriggS0B3}7m18jDNi^h)&o0_>SMvC~c^lz4eEj?k8`argjZx=cOPm=kMYK%N91*&e zu6+9iQ})u*Qty&8oO?ilyc!F4Sy^pYCTdL2Cyx9<3bxU=8+&k)VZ%0D3)&Bp8T`}1 zxY3?Bj9+HVrIjje(0uvV$ltZ|$(O%2UGGs$Oi1{(y)+8yH1vblB+rIQ&^3Jda)#P_ zmlo<0B%6m0Aik=7KCp#egzoX*A?Sg?MnED0S#do?_rO;*w;8x>=~8yEDsxP^`xf&` z%?=fm5V%{=+d=05)(JcZwEr&2mTM&{%nzAke!*%$XXU(i@0wE@E7WD^rhAG|U(N|@ z#n@;;kEPsckrY4+H2py=N9p|Jl*uzyu_YNNJwUGoZJC1t6`aUuML+SP>uE za@IY@>bZvT9Tn-852I}UTM3q<=;xNsP(D#~E8I31xVX5|`*of29ktO&w?SAq6vOwU zl(LJ33;%4Z-6z%%D5c6dD(v#nz$&3eyDX2rSI&{pvlt8Q<(3Ei9{RIzdfzL-DZhdv zreX)`SjhIr8WD6Cx4c|GeRR7L6N#-h8Q&7I8>Zzl6rWcOKSO247SU^~%W@1?yL?#C z9Y0FDZ28{A${2HA$6BG{UC;Jp^->l-U0O%y38dN#o@UA<)?&%pv(2do{Yd@UsBmql z?}(8J1I@k5%`qUO^du1sr6^&T`^#m2{r>%Xatyd8AfCAR_`Q}nFz9p?#U&>jIXiEM zj@B+zu0WIP_-E^>-iY7S%*hIMR}hUsf&ri*ba{r%P1lwM)=xF7?10TxQ-rX>zw?>I;9N0+dHw{<**+sjaG~3%OQ-W9e^{cf3kI58B9W z!S3HG35hZILnfT*R##c9CH4#CtX%gEx69%D9wyX!IK!p||~js359 zdI(2%_1ZiqW{ht&4lZzqH23oy#Oh_gY}-lSo1|NzImZJl<7Zi_ZT#`!dS)wD{urqhL|+r2|tFWf1$5C&PTWSA8+53NK6u0#iE z1`>X6{N(pFw+hwXfTe?#)BxNdDEw8Sm1;uS2@Y(Z?7w%$37J^&?|`XfIcN(*5Wb@c z@V8KVB~q@bLO4;+il+mf`S8KQ1oz(5rnZMH)~5!34X8h2c|(g2cY4>k_Hy2!MbC@9 zSlI{aX{3&|Rblh#dX1~teUqR4l&%P--g8bSld}3H`GzHf9u!pX(zrR9+piOYQg^0w zOfQ++yf#t?jt?gi+JPTTvvXcm%VQ2rF-B$ii;|*=$QJr265aRsX*VXYw7zRw*8bSy z{s>Qehai*=xYvx`86}IoHIjjeD6oFed@$XurM~AxOs#eIA=rt-1)orktcz*?m!j+TLFg8rt`^F zH_aA3tFcECvnj!m~7{6?YhAojJluH_1O0@+D*5fivu{wHGurvF{czeI zcmFV?yvmZ#7B1=!>OJB`*#v zx()^zL==Th1$E5sW{cK@QAyG-$y<#NXkSMMv7{gRfsQW-JQEoGXN^11TmS(Pk#j7D z@~?!qUi78Wpt_DD#yx*xJ5{(5h@g zg+RR3i9X){px`qNc>x5T*=@_%8(i0A%=|x>O@a4>9UlM`Aody^L}<3;fwuoF2seO5 zm?CPZu=H4BT7LXJ;?0Bg>i*%`b1ZHF0HWM5)3RxXZcXI6-X-H9%jT$r=lcRHnCtOT z5Qj8FPp;Z^%@^Q7-J}U01vpZH$?F%kK_{zOf6e1u892UxvqEc{t8!_oF%ZZh*i>s* zjt6X>B4=c}(_gRc8zIX5v|tIF&$#)jZCQhzM^Iu=v5MUKlyZt@@%2nDo{LZX!^>ur zaY`i9Ue39Ja0}uIm^%OoN=`9D^=2il06F4#Q}I}WA-aLPtM0}Cs84rwYp3@%=AcEK z)Ya8BUus_R_2@`sV`BrP%qMkEu_44o7623jdVo;UJS){_+QmZH{c_%RZ7p!uY1}SS zlZ&$ZxFIs;^3|Wf9Fq}_Y4{Ei4;u-(%g`biX!KCfHGsWUVQyYtW&_ug7Mm1L;-LK_ z2#~=AyrrScsMLgixgf0eNGkwPA&?_N1*C#a{-@hVHI*NdE z3e5jY?D0LVY1EK?t2^PqaNmj3e zM(U#%M(T01{>MDn{;D87egobE0rAwWG=k$=?=Mgi!8q#K_Y3M_fod@1Rp=s0vIdl9 z)@Y*{^gv30ojb7+*LdszHUWidZP+9gn#>4m2SX%K6;OK-$QZk|bZZQY4E6Q&rfjTb zv-+z&_o7sDGYF!Pb7W8Jr-%E3I*Fhp-zlJ)&wL|mi&-k~G%bXLjVh<7qg8OaRg_%Q z;QeU|t@(EVoxy;ikd-FOhBkoa7_=xr%4Np~S^(f3ngighg8ql2K=S;Bli1O|67cO$ zxU2iOU!ZbGdB}fArZsCdEJ-qkk~V0c@YYJd`SKkXAx1KRYyi`iqYTmQ)mH|fF%5|? z;XU*?!Jj=ot_?Z{h$uK>wi7mD*qF?_$e;J2@|FG^N9^Ii`H&poQ$P~~wkD~tKC zC<-6?ZqR{(5H8WU+|La{T6uo%iJ^Dpt-DK8^dYIwxb^D6r!J^;oLA-!{e_?@t|8c7@0MQEy$A4F9Ub7r%1u~ z1MEXwfD>AehjN9k7S#!Mc)UU&-GrET5m*z~&YoN%JxnG-r*#QE`$SDm?I&5??m2+i zmR43^;WCixZz^I1iU^wxi2-`1;MDEx>B-HjMRJ&yyEjUC37_9`%MG4m$oP4%NakP5 z;#{=Pjha%u)#%x9%WUDmRaq-RQQz8{0K|O!S716s?v?gxpnah4lhX!qzlQu*gcx*x1v*p84@QDVWJb*q*I;&BUxwLCYg4i>26MK}q zV)yM2u)bz$-6SHv2$?33=_|NWF>@UcDf;Vqo;JmCL;VhI1fvr$m4E%>NQbEl(6U!r zA#ij4@oP;d1b|&vtrWi%bbTAg_b56t==ak7#qjTmrwYMuV~03!UB&93lh}@t+xk>B zz?Ug45ftLT+N*!jEI+{k0Jj5`vqcRKiUgjr+vmnE}IW_Lua|78UX~r$(vOkXj1{sKk517nO9Hu z;yoy}&~`RQy4^oMY(v$MZ6*P*lP42k-@;&(sAlK?IpqFHZ+zN!aF%!L4e{xAwAT&hXaZo0pnBH*LrGzdJcV_F|W-U#R*>0N{pbx$B%bP$gcJ-|pBl z3vB~Xp5i~gvbr7@@WG7C|KE+D8>Do%eCkpC!P%_{EC^yDNfve)Z}m?wg8glOgPcap z!+)bP_6?r*2Hcxe^E#j_D7Zxh33%aSqy6pn(0F`2H?%&p-9#XZsPF%-+)wGw4W3*D z@M(LD`!TjauJuP}|X-@^qxYqjS#md@jyL;L%B zkPpmmu#!fbmSCDQ{;lvdj$RwE6SvcgjFd;~AG*_O7{=c#(#HIpl?xz@T?c^qNHFuk z$hoZl-{-&K&EpFJ2RqpBxXPnY>E}lhP0GuB-P^@0*uI4pGtYheUq2%gk|j7BpcRd; z$9{>=l;B6cvzyz1Ufpmj;Th;OY(S|~4qkX8KElCq`Bj{ZIT`r4k)z*+gD1Y~8=>mc zw9!a|Ah7@?CZwyc}X6Tpy`=VTzK!lzEN@BclCu~&Qn3D%w8Q}C} zy%wz-!2Pt3?drcUyLc@?X(en|zo5OY?qkuD6}vtvTQ7mGKv}m5%{DGw+xE)uZqy%= zIR5wXf%#BAGeS6o#vAD!(k2LU;YpnNE0?hMAnF10ODpm@uk7`!-?EsoyYv!rKah5z zF|*Y_pSpnDFkhK732|HQoGIswNlz-Z%iD#kAK<7wM$*ldcp`5iPSoCJ&5Jy9Gyq&3 z3MY6VU`h3)ZTG-KI<&#JZ}7g4a901vpXG4x;$}Ms0)qw8vjM{&P;QZII%8|W(3o8D z2OYzGC#IyM^SQds6rG6O=kOdbjrVH%fI&O#d|VaNKwP8$)Yv`*-im!cCY;Pqjd9P z%Y_q-1Qv;S6~q&&Z~VKfiT~K~(?p*MiW4MwrTi&#b^c~tFmZEEV=SQy92$*~r5xPI zT7wO;gSQp_ku0~4FGLR>fJ;ndGJj+GT^9&fMD_wKRw5l+3;4|{XGXaP?!yGn$-!AC z^{;Ou+&vzy>Ypp^=IT1u{YmljIsXqb;xV$N*rXq?uQCe9cXx)w*SYFA9cH%1Bv^Zl z72fI4$o5Y!e~Cw`-+H=x-9zlE6=SKs^fyWERA!P}jZJQ9w?1|I@4GE~{Mi%A+u60R zYF9{8tP%Xe+4%8V^Z{D-)_OaWf4YB$>cI-=x=8Ru4z<~N!A)-`oLzn<_=o%N8?Drs z2fqGVzARikGoK&QnLj80kX}>pZ(nrMA{UGM=QoD3h0!pBLX9>?NIdlx5R*5!ij zN9g2mDP=u;{smg~`NK$AkDvBG$k$i18wjy|l zM}*vp+vUGE!yC6F^4!B28HK4RU9Nka-WcXv%%IPGnAoh9Nqep^%z}aoVxwIQ-h;@aF}F>`F89jyGx~8nP?W9i~pAS%#?k79>3Lc(A~4f z<7-+PTVr8|7DG$S^~7*=G3(6LY2seq8Wp#Yf1`|Y!+T1Lr{EV`zR~l;y`9rO`R|m(N704%J;Xr;5eY{4EnDP)bBX>rFiG+@Vptz{$OIE7)SD*)ztLBJMIZbE2 zDJjHfxiRjY$jGRzAV2_5d(kK{apOAa#zoH8xUo4A3_Z?zz9VT;;k#&`Ju)g0&qwsc zw8XFFm@TGk<81jlkud{RRn?Q{Fdf6U6z=LcHnS`ik}R1j>C;qTaNW8)qe4fTBQY#8 z?BT>F=M1GST(Ckprz!LXubPey1M%zU3A6N{?y#}Jq{3<@8e6N#f~fD;EZUAxul@Yg z*w{$GNEv8JCt%iGr&@G7OTUS(B~d58`X-y9(ms%>deOsv(JLX%L6T{HjV2j0;6$++ zwQ=>wLgPqR?|SJWy{hjR?~<;@G`6f)SDqOwe^}5X(D2}!ZI?!`Y>&b-u=7gwRcGPLcX6(rPmjHH|CBnE{fQu_Tb zn$OLB13Zg#irv<6I*MQkpeX!W+nu(c|L<%PvVwJeA<=rmGXmXl8$2~Y&@z-kXoraqDK@l6 ze+SlD?(%kV4`MzKv-)%OW0dol9eXH|Lp+Lij?>3I$W`V0j%n_&=2 zZ%ZbE42d9^0NkYpi_K(P?~W?I!j_+<+75eaf5Y(KeyXOGKOsJTF-b-5s+;`KckDpg~?Kw*eLVa=RMjvKAKEQNl|7c1)n|`Ho$|& z{w8&$7Hm$#BO{0*9NgY8Y_XL#2aX1$H-#O&UIAg=)+=?~IQ964wXMg_TX&l`W`61{ z!w3BtXBKZIMp@~R(~|U08)?P8i)}Xqna%G3E!J!Biw|*=#m6Hv&6u?~;E7Vf|W^b}}AwO}}48UpNn zo|8Va79*uyFboEEG+aOL6_Sk8`D zoiNy8IG9XJt)3mPasmE&vYTXY=Pp3a`~JN1yEMAMIe{XHU_M-H{bIJDOF6mEbvbMSnA@JXeM5?}bkPg9L58DUN|v9Cd3o-CUI4ZjE9POo z1y`JY*DRa7nL8T_&tMwmxeyi1n8KJ5%w(Xg%LMt;oOP@O`S`$z5YaP-D3Z`4wdBcV zzz+MbM^}oYw{1Hy7&aHe5l@$IEp}e9>lgF8)5}E?jceZ0Ck7p0$gaAbCZo%~94HRL zKoeTmyS<^IAzc}?-rALu5qFqcKMc%9@J?7B$gD;e3q91H#{8u_5DEr3)k)0B0EmIr~T7|ZdtEJ+@z%X zx%ajTe2{t4LvJ6j$c}|j2b5d#>}STZAgRuVW0DZ{MyRqou1f=b7fkGffAL$XxXeOw zi*Ji)v#=LLFcdThQVw*RWIUw1^8NdFn7i`mmqp$I5a}XEgo9Jxwqdp{rJ{KjmRO;? z^o{(@?GaL0f1GE=PsXy-3k?_~nbKPv*JWz@|8X;;z0>6>in*e*5aD$qRtQjf{^#-M zJJ#JRWqH?b z@ej|gWGsKnxQE)9PVZ>Z3(SkA@+M+Wd|j*|WADV!CBq>tKuW7`dX!(S^DmfnJ~&ZQ zQ91287c@s}gu~%erfqOS0{(j3K&D~RA>)2ezEnM0GDcDk_QnsH?TP=0DA`2Ymf7VN zNGj#etTvjB&-M^Ll7LKb(fUsM-k^Sf#6Z)4goPX4eA*cV0#|(U6s_O#tPJbWaj3^c zvw3u#ZnX-u#U(AW`!36aSAlbD^h>GSXUyY?^B+#ml>fbLuaLE~yW#;GTK=kcr~Kb@>U>lbyGJk0Zvuw_*FIpE7LNV!NVv=vQL$6a6c% z9LEex;-=FwSkYg3V$FzDZ_7{6{ri=v-3ImN9vUlayX74K;s>{h`f=@YEQ?i(_H0GO z8%m+bei1-3*qpSyuTLHKkSCH_Zwi|XD$u#Qalm-fkEPt{am|C+7*W&zQe!G1z zo&;^uJ)1Ecn?n%3{vF)e*khlta$#5OKJ>q;CNL9XiCxib7qZS8b8)~E_53}_Dy@}4p6akG|{nVI-VKeA45xHSfVyh~z+0FP!JramWq^{fz2P{HP z{_dm&RW~ImsY|xXyV6V=k3@hT^4PMtY-y0K8oXL=n%qE0yfiPdG) z8_%z|LvA>j9XV!5^p<`yxMa4z?6&+4W}jWb;txhW2JCdbuKS~REBkL+4WLJt*k!-B zK7)1_#>Re}FAdG9^EbmWVT}z7FQi&c=K2nPe!P6_e!G1pp5&RaBZW+4s#%rVK2EYf%i{OnqZ-#nWXI>yWO`aOLvnSeGBLlhE)P z86gMEMJRd@0bbW?MM=+fu2}i`yaDqt z$|0VwPNTCZPV|N;<-Kct)8pG?VqK+HP;`P?F<{~}Fc<5xqxdq#4tHzH{a3jF`&I!m zMWT9XlcuGbC$$s&MrFNOkd>z%1WXppR6zNL3}trRuVnJ^gxy_=0q|^MCpNFkZOqIX zlU+K8Tw8(;boZ0t#Wp|c`yTAGpG9Za?0_Ipe#kpLMFau;5pBtaegd^S9dkv_%Iz)Q zPk-MLaHRsKl%RX5hq_x6qz;TS{6gd-pDJCkUbpWdys7r z0v`1kxe})0Rf3VaTI^QZF}x)MUdsd6^}pVEdQ<-gv{;W0pl6t+r@;kSs}}o^oBS5> zYogZ@Z8P@M_7w{UDp`fcOrLv& zwho<5bk2c=2#j9Bn{pc2<6zJqCea|?`6!G%JQBf@h}gLbh5(!)^Xaf0c-aNO^yj17 z+_ALC7m>9=wcnJaC=GzZT3+Mw)yzkZf$DwKYX>Wy=1`f0YRad9QWdtD!~@Vh+WWg$ zz&K7Wn?Vew-vkC|eRysUn;am++TaV*V@Iv_93S)?EW6Y-?s!>_s-B#*Ixc%Jb4mye zbZ8^N&}eHP0oipuXAuJyoU7!)g1EW)R*9(z zv3tR|JGAO(aDPlpw3J$rl9EEdF202m3BBnvs0xwB!d5tMHanW0#SSth_h`(n!{hM$ z{B{P?X@%v1{N1P1G4V1=i(Bp|Q+8n(=urSm0<*P(?+75NRL}K`i;If~i*-jVsXj;i zVDp3VZ&z|zMAnJK)1TgR3@|`&{IJE^N}|($#&L!N*kaSnO5JG^B&AcEliW6H&Wv9nicR zz5# z0yN2DWMH%c24|otmykJe5<@rhSGb(d5-42otQh~#3Y-w$cL7ERqz^khtS3bEgoy-(Z|S1jVZ)|u)lNXf(Z<>1 zQvk8kx+C&5!Ue%zh$vkmF>-HYZzby9F;>4jY^ZUrF_pbU#PL8Y zS>CQDYIejjSc@*$2=JcMF%#LOif@9|C>;1F1w$2JfP`7|=_*RQkW?-P2+f7vNRyK^= z!myG8XZ&Qinf|>>kdrp`XOSePGn7aPgQ9BQRsY%W^Vdta)YUwPYH&KA`~&R1(a0 z$Oz0uWKs%C6yOnL7UCfF#qGkD6jfpg+vIYJmD`voB|AFQA;Z$ag0|7UJu~hz`xjcs zKRaI`K)|j~6%KDN8Mg+uB#V`<-~|9!&kFeedNxqutrBUEVHE*u=CitdVU25R2(QHs zq(O@p9E8c=aXgUN=QU&BM!nGj%L#zp3XgA)N*S))iB-jZfLL35vP?49sZ%ZqnNvO2gH** z&>a3)P_R)od8mL5u<6Sdgb3h7z>Zi+R~m)@z;Z5tT4pnNR%)#DpYn3X^Mk9OWUk-! zfft%AZbAA%9Luj>oyEQt0H*U9tezdKa+4dmxw(CTg;aAq zxro?@_jgvFz>5oD@Ulu9ga%8CgPe%-KiwwMfAQRbDG9h8Kp-#<0iH@zZg(S1RxBPu zUwqNfmNr)om*2In>*{wW9NLKQYEomlg|HcYwtPstJDKYQKZb{=ihD#1;KV2~`I#kv z-PFEfjLRgWB7eV_cKM-Gm3C=qsq5-bguKJ#9=uQiNcffjwt#rTD;(y^0q3Vsxa=+V zpKtv?JY98Mm08!d6HGdll5XMBgVG=f2uMqJcdMWv-CdF*AkqQ?Dv}qt(juLgMoMYE z{ebWH*Elmj?^EaOSZnQd$o(I5>)$2BE?5QvC?M4=M`hl?wpsQ~%IC z!If@Gx1X`C08Il7+AqW7+)iUoV%q!R^C~0~m^d6;jgq24JU_N=z*g?j1)Z}Zq`l1O zL=EbQHP`lM?D6NyVFi8AscnPW0|rIPGz#;yB#|wa8iu`yG6(~tyh$$(Ly`JpF68(A za~Zm(jvXAI>L)ZdnqnazA0%E8Sa7-(u>IS!Rm zNTUrI(#DkrXO#wxInwT!zvlS%cEI_Few`;t=CLfzEzn#6Y{5;USf~oKOk$Z`1Ain0 z`1uiYE>NdI*#aI35dP$PJSXnM>VeTax-bA~TOA;N0eAv~DXG{;i_J*>sbYV5>hqoP zGLcEq@`hUTq}(mx(8bax0qYYFViA0Rb4^<6b_5qJNdUrRvN?&J4?xHbrPto+@B#E7_!!R<9850BY$7lKi@ zyeB6F?6il7B_8h|ujFEko<$3EP`cKa)J+fpZHrxP$p`K7d~a~ zo_7R8p>Y@#yaN+Zt%j+CTWc^ef%wz_3R3&S36tc1GEN5=IKcHVKJ%C!rkHi#4;g^L z0~q}na<)RjQm$dOJ{)yVVH;|XV&=tH6)FgPspSYwS8v6>mpCS(*qEIfya9y5l;f@bm^ovo45Co@>{?&{NLz1dHO`+!+eXj^hX*ZyRCitxNE2VMQF)94tW%{{{{m;BcAQ@ZmW2O#+@ay_5W>*>b>RSirPYWwDDQ z6hI|tJ3ZOsjLYM*Of{j~U%w8SSUgh^zBUMpPkK#|9bT*d#hY%V9%W1kbAKSo97kPy z`#1pk`NA+TeuIsDJgL|vNy!1ppXQcZ_9F7EZn~%sl9{~vl^o+bny^JB zcscL=vGN=#x}1uXlk;p+k_16Uh$>TxEPA3Aa% zExY%i@!d?|*%ET31u1fS=6`qaj=`J=I2c02!D-kYY}0@_Wu-ijS>+bvz`fse>yQ{7 zEGRpeeQx8N2s}ha7pa~m9n>!M+O0^>@zSbxJ{w86w@%z4>|9-2KsE=t=WA9seu%_n z{{|7_eh`NO4R8WktkMr$tt-mGtx~gc@K}w0eCd{ARHN2Q%?)+HER;AxxNf;oD7!U7 z*#m{pnyY8`JFujK(ID{ciy}DiVM@c)_x`tF!hv)4#3iP%@aDPGP|TLe`KTNB$(6xF|cK3>iP4B>~9<1mX9wzHD-K?r(1NB`=XAp!nS3%*+ z$9%`SeW%DXm)hsXK60hJldX1f9v7|N7v7B}*5@I|t_OEqbTGTpN`D#sBu+AdkUb_H z8C8K16PV7Zs#7>=u}6iV$pJunY#FJCXWt3YnEQR=Nt*So;syeBP%QfC_d5m4p;T;! zjG`n-Pv#^KpnK0%I)=2}pJ{>Uj_+hbblL}Ow3aNq<5Q|Mb zJV=}Ebaw9}KWJFZABr|EY+kMys(ZfnnC-#V11#S16r-q899bkgyZE6~tu>Ct_@k znv4ObPV-#b69uV1d?Bcyp@Rn{EVv%6c^zdlJ%fPB8uzAAAI!$ocuuAZy@^FY$uHH$wu$}xy{?3oLN4qJJQ5`1GZo#8=eNrb36@Z|wqUXX8Pa_4k*bYtNT4lf}m zGhrk&q;GG~XS|Uc10V}A3#_Q%>3fyzbLDo3#Qldz2RDtow*Ne0v1cI+BFo0nh)52v z{o28E`?g87Aa!AFbQEyWy}r8BF#y~h52;P66d;R1Y&0A^nx6L@27u6_LnExY*`(v4 zu@VQu3#oORJS^8yKq>j04%F+C#_TKZ|D*Do-r3?jti0PQ|Z{GS*?P{ zIA>f4M;r`rYrU4ClYrD|{(9`U0@b?riD1I*dT{M?Nl9(tA=E_H;;D~XQsJSJpPtCu z{iIm$SYd$I4cQQA!mw`jL-Y(4u&hv_baxj5O_AYpJWJ`(M!a_n1XZ{}$9<@m1XZ@& zZh^Zq>_ccUO*O@ERJz4>LW_qPcYDDxW{9>RtOG!Grerpy?VbCUOV&L0y|^4eiNUx`Bb&z&~B zeY0OyS~wYFTNp`~_C)Ho8@c_Qn%WG_Bb1(i_S&M7|962)FH1l2tP56$Hvim^eoFTy;H#2wD{KG|w%m$+8&0?W z`VsBBkY)o2>96&`doMmM4O{{g-kV|Jw;}%l>m_&{vvKL=vwuKZ8m#k&1G$5wT}xr0 za+&9+pvK&z;P|9f0qGRL-HhlG;Fj8LYP$Y=oQgO+xpl@yW4w5AmC3Z&}ipyM-+AHPvzbA4M6}3w%p0V?-s{bie|l359##8QZd(E7;&2@d?Suaxj~bfeglv! z2{}TD3AjmjJB%|;*4BwmyqmMQon5a(_O=_-ah(NiCiw79psc~MgDs_tGU*f0O&dpeQZin+@zM{G!Iu0Yo(2=>GqB*QloGsZ>gKMyhU0-lnLpBA7(nl1_=1=25V42>Pe!e)jhfIAi;`PWAwL=>;~IA~E&xNQHu=ftDn z4vEfID{as*c*pWg^A=GR#VJ^XQm8D5>Na`MVz>&*3#XYF8J!<+0z(e4+XdJI@5-aj zkF-d4!3^cTA;9M#gP_S!s)6;@5=0a#^x7ay!{xi4#TWTZ3^d=(&DucEG8jd?k$lQF z2s#MpKLPK1ZE#djn#l z@|LS4p+Y1FH^V^I4B{W4G0kgBdG>)+09_pL?I26ziVInbdmJF)<2MyLy4fv0O&M?Q zacIgdbK@M*YtiFT$ca5+(Hl3e`ExwF-NOy;LdSlNDDZL*kvJ*uBd#uf)(fC~K9#D{ z4P_@#vZVgxh=AeO+-;5r(~&m`9PC&-vY;$7E{x6!4^DM*>1Ec8aQW7IK_{%)Kwd!s zF+Kr&4F;l$2B1u6Ws9{%?Ppe*0r#R+;~ZjNB^Y9a>_{!w&_%mmijpxhgmwhDLdW4h z3wAnvzfYV|llFtg<K%%QJyb*{cWmPwTD8T=tRyP~Rzys@DX0_|p6Gva6^0yPum{Q)#B<6!A? zV@;Dv53gogeZM!7xVO4WGw-bhyvQ>KZA3P#0vNQfJNTmsMjoM4kSri_VX&vYIkQfK z4a$9_le_75VRbKd7p6#aw#0F8zgJq5j}Aas){{4u`t|u>lnR0_u=4r6lL5yoojH0%QFRB7(Q~cEOBn(%v z3yN%e&n95(h9=U%ImIr{ADrFzuT4A-fDWzE^W~O)BvUDpW;xd`8KZ)UuN{mWr~!y< z{yN~+VM2aj%Mj9JAgUkg7#U>v9hr-~`9_Rxh{T8WT?$6^xc5JrzIb}%t*iz6Yz;E8 zV^-qSJ@sjdechA5-VVBAR!r6>{wRG`QfhpGp#>t;nZ`Elp z(Lu6G>-V&SiBAEaJs^#PW(;O>05O0?_IG6@^9iFOV+@365z>B`jtAGN0?=%=c(7ec zUkrwV@8^fVu8)^Lx^-vwlXp33$uI<=XYil|xmtx{YNP?W!1cRpk1Sz?8srv)K>4QE*m|ajZ=0oz7uOyyGa6BcxnyYY+g{hBnsBo=@G@}w znl{5bwKAtZrG_n@@8zdPq&HCZ0ciuASu8Om9`>}5jU*5RvKX~~r^d6q`mk_IoV5U! z^9D;Wp!|Sd&CfF+4n*L_6%{zBpwbIW=r-cfG(0?fRafBB88F`imss$ehc5e`!%!zB zP-;LC=RL^)Bmh05Guw>J>bRMmHhJ_=3u98xH~vw`u(W@wOVK|!MECC?HV&0XJ1`KI5kes8JCs8(OWcYrT&um?VE{$Sm( zKH*OZL!&_OVg#?pqGv$*#pblU5jX-0PT+ZgJqNmt?AjEfHQNAi=655ZE+{n7hlhuT zcmBGm$so&opwUi99)ewxSKY4n^DXJ-w_T(WALXDt1+WK!@(6B&=VF2wC`&AAGFv=g zPXd_^Q;mRm0+w|6+h63FIzjQ%rI?FvH$o%9Tmo__6lTEP5?x5eLe_wg1e*b{e5jA* zbA7FbM9fhLWWZ@9@_B$LSm-r~*(+e4{7Y06f;#}jBHnw+K>QnkzKFQU;jkdEB0T6e zN2l;+zdxF4H7>715oRM##J5=)Tl_w6fzy-g+3&Kf*su!2hHY%k5vCx8o4n{LFz5B{ zDScj{vRJILXx9xw4n2_JLnZ>gz=Adj0<9%g#)nX<)#AK!_t7OShMZC9f9N#EkCtK7 zGF5p`@3AsI(ktlX-a#$?b{)1uS%R<1_VZR;ltZ%yD%<-mqbL+#OGyi zh=8z@iulGs9|sMZx%NdgHv&PF#~YTLIymt-_4jc=H}_s0yxoe0d;pdPtQD%F!_}jM zdYH^p%zFZoW)XqkyWmUmvqC5)-C0Kz8OesdG{xq#a}_vSaKi<%5L$V}w*(q^m`i@G zx8J}L4*w6bDtJ*LJP|PVBJLk_ib~7MPE>Cq(0_+6DlhU6kJxN9s-}!IJqN7TwKv^R zvjFe5XGtWslF3aeRvPSx67_J%yKdaf!Rv)X8NeOvcvhNIsk$1Hh`UEFSE@y9N2 zYNrt)Nh~1_U}BKMih(p$gz7HrnRLqzw8Ll(ElQcu?z;~1DeYug&bRA*KT_WHeNwE z9n~1Zw}6WZGxM`V@Qa^xqX1ytH1wB(N)g2SE>lOK|FjI8onw6tu|Bi29Z9hJ05L{l z5uCOHPL9Z-1DRd%mS|7a78!88gE3>)IAj_4*LO{KmD|mAID3#(agkq(aS+sefNrV=O2-~c|GQR)R+uv0v|N8gs|OSy0EBPE zCIKLfLqEFz?yI^f$jSk61jlE(Fpz41ZUFY7J2>(sg6E}4UBBB;X1pstf3-jgfo7|R zMfxrSYK3(Q{xSUNizcOAAT-MC4+l6yQj+{+lm*}u(8ycTHEj)o+DI9gOAu~7uT~6d zQGmCE%uvJS$gZU=?kVNVPKsd^%8s?KO=( z_aDX%jL1F?&6TRGuFZXXSbjfCh)lVRgb&r**->_x*mo0=ma zwT`?C7EN0lB;Oz-XWda7{qyB8wm-*F$MIPcE7Kg^v z;EY?MUo2LGxME%q=-qp`!ktMmz!*Ta2Y(qjXsGkoT(vZDkw>dKC;EKxe6UwqR45dx zUsRV1^jc=6!w!EMu-?u!)jXC7b^cn#-cr1!_^{&vgqq!`(&p_w;oA}C@cJz-|()*q0bM@PeriPOhHilxz z0J<^k{SqpE$^U_$)8gIr-QKh>nLaPPmzP%GOb!kNk@P|}lOP9F;E8Y^d`^-&4h?%k zOhAaj*2l3Xi1?{ORS(4V@i8&bx?v%bA$4ki=@x3}QbZAk8 zvm-KD!@_FFDnZcnSibow0}Y@{ULs%kMH!6r{2saH$q$2IcASk38NC5M5RO~7UU~B?V1Z(J=T-u;efZF-m(6zhIs=}XT zhZ|rD*>|y#n*>Lu%CxvYfBz9 zcsRnpg-E0g+KXH|b8Hs|RCwNpFlevN9f^2=09_(=X6G%$= zOZWFI$2KG^hvPq4tjPZz=26j>VB`x-JvR{{l~sFP{^hgsJl4!ev3XA_&RaC6?+?<- z2=Zf(1o+frK@4=_;yAZ(5M*H&y8;X>;0F71in7_!N;0)O1jT!&>=JL&GWe>ui?WRm z&P0n)T-#ahp^#2g0LFTpF3mg(b!PV-KUtB)=|EyxGwjBdFM|I-HpvV ziEYH?%n=?WK6_h5Ya&_u<09fPtX^SN!d%0D9Zn-d{6b#qK>@OtqFsUtS-&!g4K3<==)bdvUA!pRL&~6Lutgm78z&JsM@Lu!+l>?lK1rs3PLp)X`#gFq4 zLM9x30H@Y$+;jQ_!W?9@!2nz}bq^NQL>2}VWf-!fcVo2x(kDhMc zsrcf*7HbuDUTx0!-Wi{qJTu^Q`Q^AkT9Oels3Spe%8b?*POA@45QU2>E!>kXO{PHy zL5ZTe-h8V;xjs(&fnXNtIaH;cv{Yn_)sQ&+CUoY2SX|knp#sOp}fvxOOL1^p@!5 zcl|RZ!!z*)Rg7!6B{N+;YS_PsM}No3D|WoOB@g|M00*iNRAdu|(lrD*4K z&C14vs_&kKuyf;gZW$ttEQYNqt<}WrV#kij8{Lmr)^IZZYa(oTfoDE-J3hH}&-m=+ z%dN`useCN&T*r%ERx&mY|9+fmplUQxuI{#s$zjnm9E} zEo~coW0hrt8%R%^d{DGz~kG?Cz znZZ3}h_}9P-v+PN`>)oO@<8t+n^lG_B&6`@?jZvU)Y=-3OS_S$i>! zx6;yRyQO7km69K^J##&k88zw6+^E4HhmFRW4^Xjq#+z-?KkVDj%Kc}0o!|ai;iS|W zuW;0c#huKs7|J-FBSv`5h{AVZK)NRyk~YK(I2CIW#_7J6Fk6q+b->9;N3)B#4e5R6 zU8dZK34E97el$k+c+*^Lbs%;Tr0~-Uen_D!w=?V6E^5<+3SP^ntNcabK|Y@`qPsC@ z`qNcqBqXOdOqn?~G)Ej;P>*vu0k=qqwKM4zbwKVqNiMBP2VmK9vWz#GiKxD8rAJoaDZb)(KG|gd}?d2_b!f%9| zsWshfcq>?GiAH6biT1^H#*Lh@$^N7|!~AQ~uAKG!z!+0?9mYY&K*W5)DO>3);^|I> zaX>UhU>p2e574#`djr@?0Hd;%;0S^;DP_39UfJ6w-QofZnC<0K;WSEI)Di|o`ifgS zD5SdMz$s0^C23f9!wiK_5-L8(Y_?gax{f6xK3d7b5!Qs$mgOL~Ir$9Pe%> zvsl?p?_@iU1P6W`H&>onh31E;T5_%H$%)!}Ma%0e)tEg}r_r%@#RJZ?&h^_DjkECv zs*MLZhpAIrg&6cVu?F#}4}WM%%q!F=eGTKXM*Q0Y zYgfso+-~LKhz-X0?g6X0_3%`Axh@ z*=X-_y0{ra?XtjR29F@Kw>eNu)81!{ z)g=f9GMig+fi`x>XDZYEJ~>IpMe z`*aD(V#QCj2wmR&_*o>VgYAQOa@~mE`+MTQG)M36v1+_Kjv*o8*l_&T(CZ4#`)jse zAoSItC?59Xqa2fX22$1AB zcY2>Yd9h9gGkmaIm}QW(^!K7ys_q4{O%ogw4yL+Bfqdar>)vg{ny)%T*;DGSstF~E z-98vKn>6tO=2YncOMAw*cQU7_^46XNmbub3s;9PXut0TDdG_!^FHaEBL8xN~bJ5cW z%l}m|)^xS0Fm!JUEK7Dhc!a!TUioC>@6r-Ca+AXzur@gei;%4QW6!$x1kiWbGSUgK z#Qo(pAJ+Z5W19c27BBX6R6!^~jG9ofv8aw7F$lkWSZDa_5plFj1w28vlRI1DAs zgvoTGg=c3h9#~|q z{Xpb%jJ{v-T%yW>1;=iAMv$>=L=N?LwqyeH)OtN zR~4N}NdP|?m3kf?br5TBWqQ@6a|{`q7LD-+jdcWPGITEd+abTu_AL=#!ZSr%qCR|I zq1-ZYyyvhWFRuSrfWpHn&SOznfJMzEGmlp-mi2EUOU8PUYbl6DPuuwlKVM4}`~6yM*(nWV!f>H))%rM@-D$~BKiL#IvSxH$dr@xRcIc<=N!A*n@(zzgoI9iXsn2fEqQJ8!A4RWe&L2BR<9Z-MH9|A7pYv;V$#! zW^Nq2P!!R@e0H)(&>7+vWuC+qWm@levSeqS1MQleq-{0_Vn?`2&qQy29<+FH_5N`a z5;ILd zmHCDHm{&Sh<}Z^h&ADm!=tBqun`a~>?H{pbnI_?8NuiY(%G&x%EL6uLyPAGo=yjn{ z8nZ%|OPThrMh&F?Td7ute4D=U-Z$3fAcHhhL(PODe;xeI4=TIbQ1l4w+KNOT^7=qC z(-%3`@3><>40=9cPOp1DUo~uUme>f#U+H6`Xz_FYC{s@#?P?Rq9Osnq4AgG!9^|NL`Kr4Wl5Y(KkHcLLzZj0?{BEia0YH9Xhe^g{#&0hkZT3~ z=LIJm@$5M-xjAweA1QTaG@3OzqxEuUJ`R3#v&rl{xS!UifnQUwm)wh6Ok|cE7PRv7 z+&6tkJD#T!a~Fl)420!C^~Z3R693{-#($-Rio1#<$7JzWRn;aa~Qj&c%N23Z1EgxWsncg+`YG)L$zR<7i7A(EW>*Y$~Z(SOt+r zj?E6$Jpl(R(QKiTf+$k1#KtG>w-%lJYb($PgSdy^Pih z0=m*<=aP$SeRVj7O2+45Adiho#vc|R^>DL` z%OTnS_TYQ6_4Ls6@R;?LHcP+y!G77yHLvwuF6Z7kTr7-TJsHSZf!ry|LULQ#6!v> zk>~doKhYh3-E#*eOLNWV=G*#!E`@JKT8G=`Ui+79SbARRu`V7Gk?Z}R79fj1{0zFx zFfO5zioCRmhuhh3XLC}g@P)RAlWwUyi|I*$6Q`eQxak|Pv6g%>*Pu?A+~LPns3qei z-i%Z*iT_H(6jn4l_q;WZgLx_bk!+n>!6@seg4&_17vj(s{c#Ui$lBr!1fvFsjOHWN zM>)@ZH+w!3S-JfBvsK@;U0+;^=|W-dzqcExo@~#Ny3sM{ceFJfd9?NpE!fH~^Krz{ z)upznet7xgfZd=a3KhHaUc@Lnc3rDlU-bGehUStXQe{*y_m(_O)wPSmwvh<@@XihB zuBV;~?W?9iF>dkxdlW)eHvPY)f>?b{tRqp05AjDIz8O20wn6sqMX^<-N=BsRU~N~LUYk9aWj-jjKDb-= z`z#yPCSlwR`cjtCnCM9WJ76vmyw_nb?|--6M|eDF>L!LYSFk2oDL-~C-$?jp!N$CG z6eM+sWH}akB(#s5o)k&M%IF)|UT!!$pNM;H`t#s#TfYAIrgg2JGnLxO_lF{`X*dv) z)QlIks&k>4s5YTS%`A9vXTjrt`$8^p=DV51jchF>uRo~cC*H`Nx_i$zoL%0mil9<} z73x7s>prA%%AXmJe)Jxn+~tW#6tpFD+8?TxsrZd%k6VOx7vc_zq&<4J<|BQdZ#Oa14lxs4>2T#=g4ZA zVAe~`D(HU?t+?>0`ESTbVU?sm@!=>izqiGq3*w&wyD>)G9I~{-)Urle93k1;iK(*m zEx-ShAocfe>@2muSwl%M6&UN-G)&N2kzS=1%(EhDr5sou=-knZdHC;>8fLP;6@bg~ z&3v7Ymn6L1Dd8ZY_bt$-c*OqG$l9mAwNEvZ#i~V09NAJmw;t6#c4KW+M@6nY{Sjl= zG@mVa&Apog;vyf~+MZU}!%qMQ8{#S57w0Qtw2`eM)ZU zBWd4Wvi&lUYXCL*H&nJNODVh$lRm6(AwQ&-cZ2v#fuicreRx5HP(RbU|LcBKL?b;t z!DHQTn>Z4=k)uS8GsEiKryIgwTHMTDEi)=Bu294?w^;wF8^>j4Ts$S0H}E~=a3tP{ zcw;A-9cQN}?eN$*1=Qj2A5fvELG%P>sCJ9}EC|#CVqyG}Ljg`sF@{w^jttrWUJIp&o6QiX@z@kROWU5J*??C7O~Mb%b<=nq=ei^nXl zY}hG&fAzQ`i+w{aZm(niKCzjjhWO(EHraRR&XOSGSf|tF?#sh-4_Gh`lPF`JBs*v4 zCUD&PIW~4LFeCo~Zu-C?Kiq&9a#6t9rbKxg8Xh^#GxR5)G<;{4^1fLK@v~Coj_XlMLXl51hB4{oj z&D8G`BH~o86!{$(-1`LQe&m=M&=^8*~0b3Hpt4&51;@{u)nz`kzqTwIn^6;+dic25KL6E5zn_ zE8f;oQ->HE@wGkWjJvsCU92#|&RhK$&cXmSzy_S1QFH}F7ok=|YUJ=w?>?cRjDS`{ zIBsQHZDQ-l&B|9V3@4rF22%t+% z}d8CI@V)Y|dwh5e4l;ewbVeseoAU3}vidt&6=v7^H{;WSLbF@&Gf130sm*V4)P zZR)#jR`}21Hl2D56Yxx=W4p*P^YYVzzaYp^q=pe+xC}x7C@EEYCVWFk;9XW#&MFti zM=rc84Yer}jOtV;Xmu;4iS{7*_W7p~!R9l2#+1_5ye0mt7nQyk<>9G2m!cGAWg}FF zv{v}?tz-t;HM>3}xLXWwKUlVD-GCT#xd9O!Rt_~fX=@D_Sy|zZ{XMc?m@?)5Hz=1X z;?vpH)z#MwBr^(ydIocYG}7KHY?6Re><-eX%io}to4xGAPqE(Ydsm@GSzhvPCcAN= zu>;gjz9Iap1#U|fTB;T*mgs2ktKYr)xJWgY0G%tz&ZpaiRjBC}O-hzkBzTnV5KFsG zf{t>Os9`V&K1{^ZUwQA@zMj4y+8D(iUZTyM-VgUJ@VWSvMkEcKq;kRcYaf;6vCo5Q zKAZ;V!z)FD^N^K|%?;Vx-aE7aidXOcbmTXJGl0y?%Q69;TWI>^Ei8b!+u>kr*Y=E{ zC#4-hBFFxEB;!2%hH7LaEgQZ_7bvg@Z!_O%Id@fC68>@#JKyHJW4WdD%^+?9hvX0l%+EnxY;otgPVC0H8 zWRT?O#Fg5tg;Z0p`)xY!39g<82#Oq|5AAmDyuHl`_D~}v ze``>9jR`K}?@7yA@@jh*_e`sKuvBPX(|mNXhkpLu)DWZW^pg6IDC@!Tgzs~I(^^fZ zwx33lm7b#)ZH%Dp4Y4v^5?zeNvkaQ)Io!1mE;f|;Ysu05&IA*EX7nSHa*&}W(B8qz z!SR0x=V^iH6QYtv;h$QcS~#JnO6xHHRs0kRW(Udl9>aE`o_3RueVA;F6u)6u!DV?j zN8t%|7a5mZFm@;K2%s3W$Kw5!!kwiG?L_PIHS2%xDfZ&VH7S{jpB6Ky!ZfeD@MApkw7EBeg0RD9kec}6x48*WHkiZZGv{M`&3YiAQc z8l1`Es2EOCrz8az&HbKb0to4`nr|mmxt))!B52X2#tjcIpChLDHg}^*TuMqXCdJf^ zk({F^vex*pnubd!tlLGSTb+xAUM&v8ix&SY$FQY68vnowj&h*@RXl1OL{Cuhw6z_x z86f3@>?4Tr=u69i__L*ytuCK9)1DE1$ULdf{Nk=|N-$~xL*&n4)bI=z8esIJ5+N=F zwCvv*Nvpr?K8nolKAjYnVC2W(ShVi*LI?Z#Z7r2OQvN`ZJvfW!+Gy768_99j9< zL6N}#Sr`(n&#Z+P$v2Z-H(t_}XGpqG1I$`ZLkfP_UmhCvtQie}eS3aTei)-y$HD4; zn@^iAfWWx-NH(x&p7vavQn>hSzNiW*XGe`6KUoMAi)4c9dSd^(fsW#6et%u{(Tb5~ zjj_yu7;oKUbV)EX8fqFWqHqMwKB$U7v;d-3P}hKL){ZR7h#2u^nH|%LE(Gv>*HP zWZR`g2RrBF>z_*=RR(kCycMjUYzvs2TvAVziZId;Cozz%HY^-^JofsJ74WX)wnOM6 z?E|6A-m6ZTSIfn#r(6YRfnyc)+zyAM9Krq(yme@#T{q{tREVTt(iuK6I0=AWvBOw7 z2tn>_lDX0I@>JDPd>0R%OPbtHb<8FEbC&+A^^j4fo`Xx{6a*3=&hhIR&;QClobC&Y z!`eGr3bTHQ7;bps_u`y3YByzxFKH{g!8qDzsjEP0PSUF;09{X!G^U~BY~WV(vuKw| zbs@wVZjVM9JQd;mNzZ&lx(XwYsX`uq3cojjf#b%a?oncx@b0DXZLec!qt-0zaT0X; z@qpay|4|R~^?t6-IH7`u%yBqXdkug+s3jf^L`H9_9lXg;OMfbs(!^Pf5@vbupS+&! zrG~R^9`2__DZ8sa7g);vkZg>-5pE19KsC$hyFuC}K@OH<)tfHCN+P+W+V6;8zpxtO zCczcn9zP2X4#x)@+iL%1YXXj!=jX^sHjEFVLPMSCfq$engdj50J{gTR``$=DJ+b3w z(@95$Yup|coMTYj^>NUQ?{mH4lykE|x$)GH5iU*@LrK{u{eXrUrFqm-;Z%j`htSoqe8|Wpyi?*L+&ZHFcbQ7Emnz|dtmLpgf|KGK~z_0Q{ z*tnWU!h;`r*76JbEI+@0lijt)E14?&MUp#$%F><=opaB`{=ATz4;dcEZUmkat%17j z48!9{4(Xnk{p6oEe7+VQJ#`!)oBzO~zZF7ykeQ*x`zz#d1xl`;6<&QRNEbRv;FcPN z*R|)XF6TpH_v1R!5n&}C0ykk7|6`5$&#%b2?VywkX_mYn+b;B#ym^}!S`;QuB$X-? zFG+wVG9YF= z7UPQkEUL*Iyn;`MFe5hkg8p}868tV-$257`2^vED{7h)eb7kJOgwP5h65T@tm?%h{ zNNcFhC(0kyTifr1kzj(njD3NSVEa2iQ_j)!7EiP5$(1VR2t|pS;$gknirAX=WV$C7 zkt^{{O6QbbDy=2<7pfgJGG!lLIbNT6q|a{FrcvwNwM*oPmwVTzXOmaTgFDISZ8>LB-*ZN;)P=eU~kXe-B0W3 zUMUk#_n&EfnpsI_f=;X{S%toQ;?8Iyp1H(%xr1Vbyd<%D1EhT-H6+M}`nuNaJGA2p ztT~X&h&%MP^4kmLV}QVgN@Z00@8G*3*S-?xA37J+8PBV0IX2YczZHor{%%X388VSR zml{HYqEW~iw;$px`Sg_2Y9O1*n0Ka5%FOZC`hKA1IsZAEQ`y!e{~i`7cGTQ?xX#YO z#%aL#?*%KL>R;r6PrBW#$pTw(=#js99CE-kA?+ z)#}VQ8nkywsJ~E-OAHKx5jJ5cHly91W_wCAu1e0Ocjl_h2X_JLJD+vJAFx-)kSmeh!$O-{C255ETG(0|(I{AU$n6UU+TPa09^f);Fg z3Rm|3ufYF^kTndAgeb;*F8dj6oJ=hb}6^!vYL zV@+;!WHCA8r}jQl^asdESyIgp5B~s#Z9)4gLzV=Z?tR|JQeo3i++c_o$!F0@$rW?Yrp}UhzF*1 zhQiUh7hS}w&2zHPCn(tvpM2K=xkzIu)#IW9E}Bq7=oe&p@NkmbpjIb)UIWxX4nBoV z)%0ahOY{} z3_@Qv58(>`daulqL{fX?fDU@Vk}BuU`qD5@7Ignm) z4Ky6XQFHrEo%ZcF1I7Dx#~w4#{(HA?8@;)oi{5bH3qdVi6s(E|8s!@h#fp)|BaTn= zRRI5Y1-J}g5sg}zLH13Py)^T+u{*Lf+tioq$x}oqbr+*?i&#=wCpV`OlJPB8UaH5i z#?SbwFimbOiW?qM@zkq)t`ERm1g(IQ&k3-*aKGz1Aew2RulFaOeSsZ%M>5e_<63=P z&%}sRT1QSppot;_X?)J%^P_KBcEvrG+si-qySggRigsTrA);rAllQO~w~;+1<#p9u z(|)vFGvdY#^j_)D{Yjl}aub=ndii6paRI+&J((E|imtdQKG-KcE72EC3{stPAu`08 zeH^rXnyAtfjD{k&fwZ8gqKH*4%NP<80#)lw<5|ic2!_=Ajh;2F%H%_~h zJ2Fc=_p*`Xm5=Y)Qi>ZdO;PcTX`Xgb;Wsh9NtO|1 zVF5DxpJ{7l0!9S6DEz1zCSgS123)ObgC5ZDm1w98n_IYAl-@My;^{?k#p?i_=bMTL zTEK)!Q`JB_3Bu3hwwjSmb44#k&J>;PdyQv>uX&}!9>0CESe=1Do+-Qcdgd_!uyyOC zAf1fvVxDzn2dSeU=9)iH4`^vWg9Jya|Yic%&@`Lg{fpo{HF`Hoa-R1=z`F_4;^yOR1%$X4NGowg%Jb(%R*vHK;I z%MVUe9JOMi(d^f5%U|FEAkxj1?!{eTIIEQ>PN)D-%(dD=In1T9R3re9wVER70BAwi>y|IU!aqQu( zRbsQ(Q`x3A?wQ=e;iQy}3(<;|CpCI!BlE=D!G<_xY}mI+M={H-#8v~ObyO$&KdqI@ zT||bHHTUL7YjU&r(xIMD(+=u;x!g*@r-A{il>({FL(np;%;|Qit$z;qfyuf`@TjP9 zRw0gKcjCWqBD0wpQ9R5qALMlJn2$uf%wHf>D}J)e$nVo7Zoy2wiB^#|ej<|>CwD{u z4Oq6fgd6LtUu(~rfc^6kB>U~}dpe5!?UR?WCTm@)zPe*pr3-3Clg z`KD<1VM$DXqZx~)KlmtRDK~4+YQ@oQS~dRRKdXmS8;e8T;u{0dMK(s9>15`&q;+tU zD9nNmQK{(lF^$@LHTD>eO1OvfG9ExYKpH)rIAQG=5M=+vkJ^%m(X(0M0e#zAOxT&XiPnuq}kxiF`}xS@$Nq|$&_BNa_=0DI$);&CZNXwp7w;HE>? zCSNKT#hOsB>ev#;V8{mi=q_>uSF>Z`Pz?(Opf0|5Y0X&Fvr7IsTAn=KMu; zEw+eBK*`fBUn%Q;MbM=K&0D#;V`pk;r-F=U`n`%z*5^K-Az<>~AT>KuwXV zBgeOdarNY&mEr6+SK;@L+0ux)Ua|1GbfI)oEic~YnVmEKxm&E%n^UJ|8xu-)K0W0T zihRjDCu+-pk)1NiEqJ2An)0DPT|;aJ#Fgn)K$Yjx8ic*hGiirXmgZz%QZiulP(f~< z!V~#D96;#;C{-upHLSg{ldEa9f}a@*AWDtpV~(*ePnyLw4A`HyUJh2!vsX;!5Qyd27Ffi&vSe|5r-#-t zwj(_5PHJ4lVB}+Jd#vRk~jI9 zsznxJHxpYL>@|t(n$#_QXFk`pS)aGv#P(lL^l>(}&LZW=u1vX8_Ae(0x`w9lN)nGV zIQ1kRkIc*4B!{};$=Wp6>CYxTi^(2BBcAn^fV-zI^4>J$-sGAuVX|vmtY1FB+QwF& zdjLh_4*?D8{&gSt$nv9xpisPf;A(lrGvHJFu;@$;rOt2`98(PbZITeR42|ExY(-R# z^sEaq)?5#FJLc}eJ`JYR7pHWS$`a>SsHJTHM8<>sxcFKB0su%ZVl5q+qh~<<*bjAV zWCT9&C|*pLJU6^{^obfCllL&-uJ~fHLY`45!2h7A3tI(F+aDXSPO0M53laIUU;A?r zT+BH<9g9}A)4ygQvz=dH4A9ByC(CQm5v$lKE1rMG1Kq7@Jg!#AHMmI7IUWwa%=hrD~2z`CJ}5 zyLl-;?CXtQcFEf$r6{r}7t0qhY(X6sEH3!4M)!9MwbtkI+lgV9b@;{*=Zggcdls>DX ztIb}(05{?4@WCbpL0airGymdl6?zFg;>`I+_04gn=M67fc_r3J+p$C%L=FBy(cfyi zdp9UWoWlNtxadpUT0WFn*LhV|>_^92K~4Pw8(4i+(^IA`w(E7bz(ajo`d8;|9Gd4c zXDgCxeX{ZC)rtg--I!bvahfW*<_NbI(=h;u;NZP(k{JR?FY5~(;X4(O+jBF!*R@{MQef~Ca|5m@yt-Mq# zPb& za9d(a^Y8BY_AGTtMgu2#O+sKZT%V1xXw0})MBuim+|kM{?9N43(-&iXh3l@W+{x-O zfVrU03;~?X+?@BiFY-PDSL>?Eu2~o>K6#Pd`_-F+{;H5h#(0&8`$Z2=Ke;O(%Ap~e`HU|ngr03f z*>0y&m1EQ4sT!C1C3pI4p5d6E(~yvb_B)t*TuE#naM9E^@q(Nl^$2?F(~^}@LygzF zeB_13v=6-$;nA1=oU4UOLL;Cu3KUmKU)^mH2N31+g^dI6O!z#hzGS84xM4OVDxwIJTS| z=Vtk32Wf125ty=B;hUHn&}vLZy1!k@Ye>1m}92FsG=ayjj-y+mCfb zALU`OJ+)e7clz~voXz=>-3BS>mrS;AGkga>3^j%+AS$B#K?O_Zp3Hk{9l_*Wt+j zIR1wIZQ)Nl$kycZ1&~RIB!bRp0P{ zeBXjNv|OqFLf7M4{jhE0{vM%9I7Q!hcVpW5wWZmIDpa|yMV@wANa)w-w9nFO?01*) zkhOw9uQO9C7ROMipX;7doOW^*@45CnuH2V-v^S zc*clpu68r@8?Qv|tuo}SRjLGCKQ(ocKYg@Zd0KcV!}683;$?8nTZPS|56qcR78Vva zgM)SHh@r1AhU`M>z>PJ~w1NA-eT$rj4gfcqAGX_;1W(G<4M@&eBU$Hj9SKX12q9zu zpvN8e&i%cw95&w6q38#sKX#3aRd0Qlca38i*b2sOtNnB;v2ZcEy38v6M}usgDVLyK zUq6;QUkvUFSk_hh4r!iUNizNb4)k26B)*jikk6b~!s35)ugkhbG<|Tx_aUEo<%y(; zQQ-+okKqpb5WqWFSy=~`eBcr-U=j|Njt}6rnJhlIO>jC&0G59s;MQM!+Dcc-xIXm$ z`G>s65P5S(?>qtlQn~#e59SK4*ZwH9VA?OuT)UhfM2j{+JUPXjxVPk;4JVqD$&^B4 zxr#A0{7Jb(buppkO&=V-R`xFkZRXuJ+QlX@wJU_&wOEkNFC@{KgrJa z0ieg;o=o28a_RUs*7_inU&Csvs03a{+B_?-B^f=PeQxD#`?q9FFW9%n?RF?mgjp%l z6%c!Aj+czwD*Ik%IV;l5wIh3>@%;q=CSp>=Sh}v6hu;m)vd6ycnF_5beCM+W&&o(RniMEr{|<3kZzkzW_n*QKKOpNfcoI1d2lj#qDJYwl z842Ubt)XY>4ehpeu`kQZQI)TbGLSmfTSY}MOp>%NA-D*4m&qHMwhq-|St=Rs2T*)d zN=b5*nK>VsYMu%>6xEN8tyZlu?<;4RSF%!%%EMSlZ>|%>2cLUbYb1MJSBs+LY1A<7 zoiUy3h$r!3wyfrSB$$}(~8IP5x#+)`&F}nwR${}8&rUha6%OHo$&`-Kq0!Vr!xzDx_Nl&HmL_M1IP0J+U)-@e_RM5s0pmq~ny?^tzb9M#Z|UzPF+>^Q1OqTT;@;ItET^HnbLs30TO$@6{oh!3S8K~}e`Z-^bPWU)jRk$8Gl zUW_RYDiRz)rt8DAX>UWn2sGgGMnU&lAemf=4rnzZazccJ3np}!ipJzGpBlg)6yT}} zz~7wC2#pLFMAx8g%T|0sTD##k&BuoRTjSjoDPD-=nA5}JEZCytCf|M*yVztO4STqG zB0l-)k>H{ION)#0GO5*_DEhCJVT}e)#Ak44Cp@n!D+{BP99gRO&Kf3hRE8@4{tkDR zN_c*%vbyqinSWeDFW?O4BdFHJ zp0Bzym?F=ruMxhQlCjS5GFW~Ih4g;2h1@U}tLuvLtNj7B&cdhp<`jnt;UY)X_mlo^ z1}ROMd=eoj3dtLQkFpjT%G&F%R;4}x*KxOqJ_5933CR(MS5(2b%%Q^yA_*2jGUCU)nhG#T8ukOxGnj12SmXE?gIN@WACSIwy=|Bo-S=yH0py^KaiHB>M> zUVQh<_qkQ}L%+;^LPW;uN>{vETH8H?kz^lxrRsjfa{tU`B9rHe1(9M>6O+SYDU)e{ ziQI*;QQ8ptBR{XwtLBFG)d zK_77%jSCV{h04{$*p>p%{&*T5^suViDqOrs*WO6=%_RDK z&*zVK+7C?zbUQxl_P^G4Ow&+z(N8BVi{eimcc>fG=$RC%1MEoZZmin#j?3?lgf~$VDH+ZAiq^w!* zx=_JOm3St14IKU18q)Kc5-VvAD)A>J+syz^A-9-W*rr+E9>ZK~6=zm^vOJYf_E2UE z6BWQ@dzF#=FscZp-aCKg1eH)Z!dh9r4@IC}&t}|m^xVDwsIF{OO{M$P#JOZSr3@r|rFZ$?}GQ z>yCcTa+!&|WTCwAy!m4ASJbO0*E@D;RZ-K@n&M9c*doazlwwDb-Fb2H+IKGB45jBt zr#(R^Cx5@Fu&RK#g30!@*3IAqyR$K>Uqa@(tkG7){f4mb;+*vl9B{B z!T6~szEP->NC%gD*gN4`w_?r3LmzL?<=e4^(cMu96<*XU2$k9EqbNHk$yu;Jue{Rz zj<9?Z5%aY!oy-u4YY-G+esR#(z#rzmNe&+_kBVF>l$UItG|^rr38BW+L)Jm2&%_sZ z!d@eMWg>Fz8v1hb9P!UiK$}qcAVYC~#A?VbcAYV?Brc(n-uG+039sv7T!fGsr2Hq6 z_$AxA&NzPf-BCWsp>tJA~ufCVHMXFia1+vlk$YFqoUz?K~-+CkLkRUtJ<;A zb*Lg=Ox-(k$@GMUP~FjfXLhM{0sO)#^q3bf2E_A{0fP_l1E}WF1KZc#PikxtKrUfs zZLL=JHWb4);>X=wp`u^BMy*8Gsl`Nck4Vs)DL?=xXXo~XUC%zMoeV?Q#zQ6cVOI6_ z4bt(pi|y;D2J8tgbLZR_H}7MjmQhrp8JRdC7(gX+jh9)5(XfUn4SR1jbtM*i??vwz z+eZ{`Z27`aXNF_y#eM#E{0t-ySF^Y((R~I93OpANumS_|-8!%f0YZWfG&Nrx{sX4KG`Q|45H#CnF@kpX_viCYm zQ$C-ekz(bEAwK>WC#SE6emSqqaf2`@Rq83uZ*t*#`?dRzj}?4efGUxfO!+3b4+peA z+|DOd%)fF{=^npE!jg=yWn^h7Obb0dP^ZxBm4gY>MCA%TmRVBdz)|NExo4gfoEN&z z(4fkotb4b&g!U|(N_M;+G2?3<@(AYdowKG ze|}M589Z$x%RxAPiZLvy9jfl1>_;VFETOz#r6-jKkvc8w-JHPJqMk&ok;L0C!GyY> zD+qt{Yk*3It+>u+)wRd4l|J`MPBO`E-+$VZarIiDqO{`NPQtYpy@#i~Ur}DQE1qWZ zmVNN#>_`ohH%?i{U>QxwBjBCZYfPJCtTNZYJH`5R;&MU@Nv|$r5<1d;!t8x+ZVl?f zvyIL0=sG^q*KQLW-|;*4@1Q=#$K*bpb~g|{qeNFk>bcuSVunl68oNt*XfBWw6pipe}qnAcq z?8)i zV#ZfbkmD&^f)rznqw-sw-VE~MJJaswXYZ@h!P7!c|Mi75$+^YuON$1RsmzjEcdN6{ zA|8lk5RB5LZKo&C*I{knlY|n+xX|v^J(OEML*3oW$AiY535%tYpy(CkXE&T~GrA?7 z=*G6s4n8x>d9*h+_D+~CK=S7#GcLsI=#g}xkJ)6WD za=M3FN*7NuT&XYDTDmQXDM^L`?wK2QM)$_n1T@3lB55I6xVWBU9IE0txac;ScmWqki z#UF%6KMxpw-_vNy+D=pKmwc*@lC?j*+UvkwVrwV-cJ$FVGf{VUW|oG}m~%TLD%^}s z_X(t)RC7p=yMI=m>F6S1jcbl>=x5PLI-MG!orF-q@vEl{spDsn^d#QtMgb5)%;zCe z_|X`j0=1J?yT@i2x(<<5^}g1*9oNYkaXLMpPckEFLLk&4BD;i*pCY1~NMVY;U6B_} z=0KV=&u75h84;(wsW;_T{P>i8?aAqzqZ?dxt~9b)(Wqg?j>*sI98^BrZx!eN#xWXF z23L4^C05RX2q8EqUntMJj9Wb=c}&*#;`hR= zTx~_F*XwV5Uj6XeDi@RHN=8AQAXQu%e``>6yuRw)O|OO(+v=aWmbIfd5o{S0Du(ZJ z`}COEOSRkoMNgu?7W0xCv#l?t@=z}GJldie5uesZ+Bl@-=xQ@ZZ=>rC62ajZ%6C=z$u_}i`l`7l(J)54Qj6eiFM%89HQ7{_mQNK1LLUM|^-J3gY$aOU% zGT6~pa-xd4_#GvM`=8gZABkx)?WTva3EMi4P%~yYV7lt{ZX*!>0xa^3+{5?Wif``b zmR0$Y6c#Gt&L+r#4MSw7#4o%qsWInWrrKpwzr#}TFAhE{vF!fgEjOm`r3bnPQ?%@! z&~h4JWYIG;5@`4T!R}op_?W7ff>%heT;M5N?-qx5;QjL^q)n~&6rZ(CnZMIS$fY~` z^J$q~Ba-VU`khCd$E%dVnsAmpLU^IvE_cyf`jw4cfy;vJ<7dMYI>j+mC>*ch#J{y+ z#;=XE{I4qxA3D!ar*j8$r0%!5XR1mr&|(M}2IDm}ISzQSBvQXctuzt?3ntaBuy$CEF`@G z+U`4*7GLMcXo$zTnHHl?N!e%v(>ltd^QmM2E7W;`P{D z3Gb7=Nk$hU<(KddN9n)}Zz^6bf)q~$NlaNzxL8bvq)OS`Rao4z8FkMVeUoy&TEUHt z`;py2>vK$0Ie}^%s@>j?<*eZrIy2pNz-pXZpzi~X_eT}X1YI9ZVG@Z#t@x>QHd=40 z4yFZZwc%@3lJO&%SJ{Zk|C}a3qlzkQQK@t39M~i@hj~Rj?A#&?a|b3JQwQf5?LuDs zn7l%Hb5!X%#q(??x6l@<&80y-eZ5m<-FaRvL=u_NVi$H}Vr67mWF&V+5V-c@%lFWt zv1*T0m4zg#)4jfbP@%ktN7%t{MS$;BlU zF@1GGNjp@&yFg-MFp2fTuDT%dpvClOeGIH~))YIGt8vG)o#XbsI zvbjlO9H0B_ld!tpp-wM9eLs}{5uKAvE>exni7bgKFq!Pd0@LFTrqx3-&M<;QAx0M$ zD@8;8=MgcgXzK=x#+xr)Fa>Y4m2j>n5tjGuiuwCsgOSarC_*fZ>bPHY!BJnR(Em@4 z!u50Gnw8bwgM;!(Pm{ixX?P77e0?ccR*TvpD0`D@S!2QxnDX^h^NC`XnWaSJTfuQo zYTRV6A-BV`jSQyO)c%%H^SIp7Z$8{iNMozgsecfh+PI+wSQpxxnpY2 zBL&ei?e9v;guKI)_5p+nLt=4;#9k*AH0OGR4g?wXYxL7>xC+@!8zPm62+T?!SNRo` zi;s_b*U5++7UtzStQOC3AarEv6d-$o`BJ0A`-KDln6YR!M7m4g zJRnI}B*{hgh((QNb}sAKeUC%Sp0U2wO@A?xFqB^f$0|qx-dZpzJhkwFj}9g442=l~ z%Y`}*#FRE-N=LAUpT)E28X@xUCXj|bFkjbk#^eKe;$>k+@v^PHzO&c**6kt7>vGs! z($qmCF?_L?5gW_wjboxQHM3<`7`1C?1PfYQ!KIW4U~^YIU4G5gcnqGTD&qR2U^4mG zW%3GPw*iX`+KP9OvePAAa4^BXshAtvS1mY5-^m^--65teM&X!P?V4*vaiPP3WmlD*dfalm*>UJk@*7un2gB_+ zV-}Rd&$y(6XRkby#OW_m82&C2S5<1ilcr-wRY?9PI95N+mWiM30XZC9pRlOcaB1N3 z2y6r;j8Mur<`E|LQX=P=SitG-h+bU3UB>-RwoI+omn1@pM1SPg3QfeP6H%5kW~^i<2W) zdA1ol`}p^XIx{TD2DC$>oX} zOMDy`sTh2N9Fsx9p+M1YR1$Br2E-aCjd7@q+|u4EB#D&a1Gi%J8X_+oWO2)-;gsh& z*Q}i953xGyl1x(g&`vfVsSKV+m*c~SGv@=Nx{}A{U-H$3e+)9dyZ*bgs;)(JP^l)I zTtUNjR2X&MklIc1#ht-YgabvcXYIms{m7~pQzCp7b=+7u zmbo|}MXXhTsQ0T*lP?rF^;2#9;s0oAEx96#`S%ikhpV0#XpQIe!)J$!@#fWji z&A=F{32ka84i+O+=+%fn{{ovjep2;OSKn+;zYod#5wvH{fzz)Nr~5t4Ky&};r5nH7 z;uQRUBe2tfPhV>ZaF(J~TjWeAyFGqB=n6Vq6tC5vj7=r_p>|D${d_+*UFr%2=Am^; zA&(30jJm|{zTW%sOs)UJ0=)Yvtvvh?0!!5;_`*c+hPj0DzM(tI4$kPTB97lVhS)N3 z)Z2FgL2_PAt?2uW?kSzeac>dS&B7|CujIRu@JTt@d=Gw7Yd~x ziT*vKs46a{Cox;dAu$~Z%&vGGI)C7yfp%^Rd+^ooX|U1qNqmjFL(5c*?Tc%ORSa!b zDGw=GO9rp>!iuj0v zJpGr2CEA@r1zj)swAwwbacz_K1=s#Y88`f1Z}BWub{U$zl7;@X#xtCZ-duYAT_2Zn z0XrJ*(G$$Bzff;azkkV|S+7MiTs!+&K&RGiVcgEF`?DElJKEb;`ELp|daY%-9fa+& zBpGQO6Ne|gx;U~Q?s>(yq+pl?*t8k7bBR0d$w-*E4UDzi%jvsG&72|JrpLS-gUGcn zpQ}4LJfSCwLgTZ&Itklu7BsH+V)oy|mI}U3(cwJw7s3$j_wH?=<72h*24@f)-k5n=!f*6meLAy zDz2ht#uX|W+JhSml&GfNLoSk=ld83O}*_tV-*a^ocLkSCc!x zkJUl{)@BPxsWgsL=rj=D{;V(Zkx-j9!B6q6u<9vCm!RQ1Ta&Ke9l~zI13`|wcg6dD zqkdGfum`%_(c=jDB6A?v!LKbAZ}xs(+O}bLLGb*Kb;Di#ZYrhu6!uVlc5vz$)f4K* zxKVGjFlUwIxs;M<;||*Eq8=MfLQxg3FK}wlaBxmBPoBWnu3!gCE5Qzac?sq6iykL% zDu{QvruSVPrFP%|QOJ9{!c%v%)kZgdFE*wyv78;}e(g$RLRqDChW3T=&qr9a)6ZBF zEUMQxvfv!ir}tEUo_@Z#r=Mge7FR79Qzc0=x@Gr0R;589rs{I^NOm_{q|jKoqDiy~ zM=6z>Q@uS_3iio;h=tXT5Du%C*_~xL-pAi>a8tx7QWyLUGt!ArT+n5G%cSc0p)F3D z;nX^XumCsn%zpSo(%L`Ou2;{e<8-m?2}{~nWw;v%5E)Xei=|gzAOk0P&2J0WJ8lpB zd?{PVhG5>PzsCBw5-CDg$ezp3s$V7cMm)|ClQ?|FF8B$CK>~ZAfsfa}>;(G8Bb#@ecRbx_=B^!TrDA)Dt1_a~jnM8fDYYVY{1 z?Z=ORFy~o1*5jz zh;u_ZVLgY#Io1pX%GY*g=3adFe~WPI$$#ZaVW%&alfqhF#CB<`cf%r|t8n_jAIBP1 zo9m9qJUu);9H~L0U@PU=!P|C|qeIkfxX>#?41@cFB7E0OWcl`KnS{1+gq7;xHvu0^ zIXa`Nukw1vvh~+=j_)@ zkMVtSBr3i9KqXA(LR}G{IWnq%$UR#ef@966KX~ZVB3)=8k-&p zI4mp?V(&()jw~|7S&Lu9^q6oezY0e}Uq`MX`>f>UyJ!*)*88c)w9b}}^b#+O&A(i7 zYS+4wcFZSdfWsd=7=K0wcLv5+7f*Pk6X5DScG z>)bcq=EfS}-WT^V7@?JWB)wKGxGxP)R+~vy8A;BuQMeWgaA+9j|K}$vNx_Ww4K;>U ztR{U1QPsIYxSjnTVUt}Kxlg+? z(r-s`)Z3aoJek5bfEcIGOi#{r9K0;dG26oZa&GVmYg1ZS=d3mF;DGX1*9rej^MHZI z1XJP+>yqR7licG$ei+R3wOAfWoxWiEMK2|nUx}u!!(UxTg#FxHg=&0JEQw-437$_9;m5C5Fg=N|U>l{)VNs6-n#kVa* zBuh?__j_97%4Q`)1k z$P2yNR|8B(&q|j4sbVt6B%Rjw>2&eSMo+1wRu?m&U95hn;nr5s z7qzaXoMlNL>-(*2oQTN~X37dRQ+-C28hwssB?;p^kkBz=pXP8)LMPQ}?TnV*m$CO& zn0Z~}?YKvj3aZTe2<7gp?@wDj`j@YDa-CBxc0flUb?AGpd1{i&xDgRz(7tkFn@Qk8v{jR3%cT)qlbE)cRu^HX44Y>`?=BGx}j`TIk zw+IH6b7TamXh-CkBCyIkdMPC_?k~8OdR%BIJ}Tv~3G(J7*gw_Y7tzGtsTS>~U}C=) zyXGVqqn%IfNW!SAadB0s+kj4_B#L?U53i%`d2IvY0v1t2p;dX!Fr_e#W zCm~C6I>GwzmxW2p_g@ZSGDrg@ku zd=*o|_xiWQ$0|=3KB>e@E|Ub`SlxVgUSyp^)85H`l@qIX4Y{ah+_wg`6arChhp6<<~o z`!57zT)AtkYdca?$7R}Qo~$vl3~=)lr2C&QiFex5T9e;r|A|W@AKm_;x+UrVEyqI; zPB-y6?NVl){coA2fo#3F%8yw$;E9`HsyK5+PCMcg_A!xkCzErfkR$7aFs={}iy zpPAxIY;ntM@LfoaBKR?KTe!FwVNp!GZWqF=Xz?6c;iLB#O zX8U$7KH1S{D7qALGJ2UQn_T&(-17^gjV{uQu-JB~@;#2Sr%ZG|lW;yfDUM9G@WK76 z5qegMBxThnTIxQ$7x?+B!=)c3Ffk;xSWu8_WSt%=Qr~#W6-j4jp}qd6M%jJ%&OK)4 z)xF%}iA?4X@xfQ#>OJ%HX)DkaP4~Om5$kGx8jJIy3^X>IkSw}-ap+U>%v+Iy=?IHL zCGW`2!~K@Ew9dw}HPz?-8E&xjKa_)D3>}Id`t-m*;y%+2aDmz2eGfAn$v6@(J~HJ8 z)M4;bpbp^GU~sK}k2$7LU`uR1r@_|6pvp*oq^Fc2qE6Wq8za(HDQK zTKZ1ih||mSbfQjYO;=}zJzomq>IglHY`gOL2P}*h0rf{^w&>w!-^%K3?#fkOt$kkI z-BOjf)cyQv31C{@%2ph2?53K<2nOCe!&gz}_buP}uM>U3G}S!NmQM)0V80BO!C#gr8wx~V(rdPY{-G4Eil;wTue-dF>9&K z&(aKcHr~gQ)oD2E0ir)mx9Huwcdz^UVxqS1GNN&(Nlb3ABG1RHeOKKeT~5e&=d8ZkSq&0< zp-M6~#l_KL3BE2a^0UjSf~gfleCTH3!8qd(T~lE@pM}L?qxgkH*0#me$T5LrF@qJ zG{%`4JV0&))v`U`MTtl8WE65cXI|gB?G`9dky(yV8|geE&8w*}RR+w(^gjUqP!+fNSl7^~+dEr=iavQx%n~-m=}Ja73>}$E!2` zh|iz2E7$3@q*15K1wOr`;>!#1(Y1ddDV9FIQ=sedX*lVBHW}412Se6KdRi*%Ye`Cg z*{y!%82dOh--QCD|8!NB3ALx&R_MZk)CnwzI|h9Qi>WRUsz-)VUN^<8_WZf_FJpri zl8E%=?Y$&^r71t@_!AmQ;AucuM5DOCB}R-27K8~!PxS9tfG@uYdIM$$(Jw}IqTZYu zM($mZ4YzmzKoD!~LWGLT}vDcuQQ z{&Eo&tMKx$HUfZ%cKOP7fld$JA2`;Mqj9u*m;P3K@b>JV&Ukv_`BpGngkX#^nN$|T z8~h-4-&_k0)p~Rx=dCMu@%4XQ30Tg~okjdwMoXb_UfbW%A6fz!0d@sq^!L~HVcg9X z3jjui{{g{rGjnt07at=$W>WtA-|0yF@{UsKLc`D#nXv1Po^!yEh9~N~a<;Oywc9V7<^_7E(FAVr<|dA!*Ife%27 zsyz0quBHF)v(0nL&?{5h43-!hKftg_`+TMPbNKRR@NYTVIMowBZgCDeZYB(;{NGp4 z$cQTs`dNaWQ&$(NW$)|b$ROE&PlrE&puOmSlO8H<`xof)?>GN{{YPzo;Ro2&1;ftg!_ecv5 z4GbxUj{vzwN}j!wD+pFe)gk@eP?kC0B}OnNVQDXCc;6Y>{{B6OYF?sr(T&jX_YXUf zI>^U5pli;rQPtEG@UF-=cjeX#AR_bG)NKidPYy6dCX~{PkA?7Y;Q!$}gZqSrnLDa^ z_f_+};Pt|6R43sJh6^HPFg&)0J@D%=2&(KI>G)C4M);!LPthfLxt2HcgO931C3}Zo z1JGwItgN654O_a~u3&y<-lOx<1^^20ZcjVCo1Kj)botHyO$vYYV7`M^p%d~ypyiBn zo2ua67Rsc!a_~z9#I|UG#t{g>;9;Gufjf9^wXqf+v9|#sOPRNS4P9R2!oLibTczEkyq9NvOuc_0v>+T zOg_5~Y(}X)23LQmd9RF}wP^NTsk*jcw7$D;hu;Vx$2%bpvyTs!z9 zJ(%02;q39h<2s%m4vw%s+ISQhq*+8Xyb1EuV(HpoB?+Gnf8K^b3#)3g+aeMZ3d5PV zKHjqaJ9BvQuI=sZgu<2TjN7F)e{qI*5Ay$g1EiCAApkZCKCA{&ENt08`k-R9%7e4P z1IERhQ8?PdL-aPFXx5LEGdH^h(DiuTT%SjcX8(Q;m;`ASP(u6+Zw-Rlz6*Em;dK%H{Fs|7@S}`V z1>=Xey)1PsFAeuB@Zm-}9tN2JDDKT*vR?t#W@fM3+uJeOLnUoqTo%u762>oZl?9y3 zQRSlazY6-I&0g|~{#SMMnKE`xgsa_xdB=TgF$|yk?0oU@^SgTzKzbRVp!nPdR>5qy zMNQwgobPfE_bL7BW@geRn-`c-`dr%@be*>WN8c_Mo+~J(lf1D)8zn|XkD>=Gr2`ra z@hTIFtRn%etYqi~hE0rWq3YU-5jYV@0r05-OwBz&Tq)7PeigeryD0~fazIyze^ElA zP$;h=&Y{P3Rs#>i`saYT#Cx;;_Ji;-cRmW=DEMFW{eSz%_Ce?UBz|&;fWSWqG;5Ga zk0DVw2LiaB^11l}%pWlQfvbl>0%h7A1=8h@e|tkh-xrE`o7rz$ZK!I0o)&=e`IZ^x}hQB z<3~%F6zTXJe7sgEd)xjmzSyI)_8&jFH7~8o)$?w88ZV6qwrwRVfXAZ}p>d-tz92jg zklDYf>GID0C;!&Q84s`pkVt!8A##K(ingkZg#Cq2?&MC{Nu)PSdutMdL#J8h^S2)^5E3N2L1d6J*Hq{u)W0P8!clI)D|fx~`7@t9-u%_yrgU zq?HSMn@g~}A}~>_mikPPiuTvs{5rt?M8@Z9r!1Sv(#M@3ZGq&bfLAx?h=#HiMB~@C z?f@{^XR55U)Mu)|V@5RS_Qq5)f7|TrDVPf}HY)h)-11~QiLY0*v{217fTuLtvY$1H zS3Ltvl6G!xl*w=GJ!c;e3e3XMun9j{sCB3`&M<#E@g!Fe7AGbburKiUjh6M3pnOmC zHxY#d^prwyER0!Y9LW|zh<2=I{u%6nX2Icb_#p!q*=L^(S;!7uGGbPP+}yN2hD3U(_#qJK|aoU!6{n9N;S}@84(a-hISR-dxe)#RYV~HjqyaC>$d+l86t3c_8VA z)q~K`zGrT147!P!fB^P-^B=D(c9QoLVx*G*hAbTqQoi^R9q(lyw?U!MNI8VasH*mX=#z2{@a5%0ox3So-KF*|(WCJ9j$A_Pe;~*-u?F8+3RSG^dKU*V_DJr5E^{`N zp`L>tE!?po9Y=P3P}L8|FA-MsC0+Y{?03i_@Skn%)$tWbJt38;R)$mM9Q^oo_R;Ti z>oR$Q6rha=rf{@qedORd+X&MPnxuH?#Mh9^*h|n?uCKk78_rpUthGbocvHd7%Zq;N z4maF%gGBXso#*&|$bMr;*lKg}Ti0A2Y{e>k3^RxnFVK&}A|J?te{ayA zJ^?k<)#hERxLh)r888!3{7lFNAFy@I>DBcGthMg^I@(`bIM~}Hz15mMaID`6w4*gm zMSL{~DD^BiU&u-d$KdZ)a-eZQ@cl#~

-+AlU}qL{#Mz<0X*dh~BxyMOx^hY;3$v za&dpGr%W%bO}FEvEBG|qSKblrkYat4Ni-&ReEDaIb*xs|=Jh*e?;^Ui^rUTCw zq#>3S6fG3RSx*1Z*UAzH*d*uudn^y z55kWSzg)hu%$KgA^r4!Aw-7I`h3y|R&h_T!OvGATXVvoP!9J~I)}X`?!w2U*o$=2B zvlbJv3Nj(<^CS?a;6Ly^5EsBw?IqeklsFqGvl|9zGh;jub94d^G0&yz#GbD#*hw;uNVyo zg-GKsz5oj`1FNXj)!J#MPdo>A8a)DaZ)Wpv$g%Fk1Z17KN2iL?k8%LN1B(hAr{D-n zOKrv2@Fohkk|AH_o2MC&;Dch;h{qJ;NwdW zouGOO;sT%oj8EY4E(WX%?|2aX43`LivAX?6@FwTG2K))4ZL@_@h|7H@>oFWq@M6B~ zP&p4=T#sL{frY79jj21I6?_O$25-49*RaD$jh})!;}-@B0@1h!;IeLi3Sxb=+a)^U z+1TY4fq9M8@s;KFGQ7o5G8D+w6P3GseJK-kIq|1{AOZ$a?s*73^MPYX9Y~a+ObBHm zV`In};X*Ei`(IFi!O!*cp#6(S;IHT#JfH#rT+H}fYj^NQa9FP3O?(ub`N0_2nhj0| z2(8;;VLMww#+L@*WP~SN{qWpNC4bfn|LKRX>{EeSx^nS(1R`qq7D0jo+F}hKibR9g zDe0>XnMj%|u&-vyP7$2Cz1y0*6!1LwQ1;ta^K;V_esYNW?lIRC4w*7_Nlhy(lyDAw ztHLpSkWDLns0GdGqHEc?pVsm|tu5dqA_V9;X&Qcwj2E-7{(KX`=iCa1E7w3BlP=;k z@Ug#yZyvz4EKw$u%>QimT=9XUl|Bm1L?Vlgoz@uZKw5FoZ zgm*CDj=)jFR>oh&qMf@WoAK*C=S;(c-Nj$$9zgWYdw8WC%mq9P#HPp<-xzRx5NtQr zK0z6}1?>3TMdeMqIX{eCb8)F~_kuVuDO&{`*ogVBWCX81Ys3>!gM&A-7>7L#o)(m_ z@lQf=xIq%OMG61hg&Suh?ia-~b-j*{g1~}#vO|t!W`lMtVIC3vPX+s;Uj)=6+&pKQ zQS`L$tsZ#HKt7sV7(JDvkraNs|LRyJqj2}nYUSvUTfj37X=gYThN4$3aSo8W%{1Us zql4c?3SE$5&~BJsVK7?CbW*uH^M9KA5_hWB@NJ}$WGEz=l7u8VWDLcQ9Lcl`nUyJt z3`vG4<0dH*l8{U%l4J@Asg!+$BP3IjnRcd3-@WwvuIu+7d|%hPI!;)7t#^2y`@Wz1 zeczWJEVb-24n&h+ZUDAbP5W5xZ5#I{U_MX?nw>b(8YFAVUy%CXFi|0!S{O=2iQ((3 zvoea!?N_r}=;@{v?>rVqZH9D6KYoqvPrsl0jfL6L0x_{eW!dKjXUKe(C(m^qBF1_3 zLUMHt4l=i*9=OcdcNAoc7z++f_c;u_P4A-CD4^nV4coQz5uf*GeI6t;qBK`gv6)J{ zQCfvV8IYxLwsUP58|lVZ+yJ3H)CLHjLY>1?PgfF5alR@BU5`lHixvM0fh#JQL!V^1 zyj%-lg02gyp}e{B9(&f`64~_FiQ(G(t!I*(0S4UpC|P_4oRvRoZ~0VWWy=K_#^sj!#VVkF@2z<_Vqm7QGWu%5nSLju~Hz)~_aay>eT21Tx({7s07v zxmaUVYPo*9d)xW)mSJ^+xU%!V@h}7+1_%S<##lihCteJPu9lZa>SgU7=@U7A6e0NU z2SZ0$d>>ryXMAD9<3VdO;;nZ2%HP28U9yeS@>)bG&aJMozUEr8xn~Y-=KsAqSWszF zjk{;Au&^))r{&_ba|AFOC#U0a5_I<}zV11`l}%oSs_brXqE;GX4P5KCNMiDw;O`Xq zL|r1XOfOto{_O>n*hFg8Q_jteG&^1^ed}Ce_*2@|cO%zzPqeUyrm-6VuVcbrteoKn z<*2V5LLesnS3l4Y;|`@m)8K{>(^F(QJi%LRV|O~A=?-^5<=*4LIK$#t#;*K1JTaBl ztI#x>OlhBOVw`67>2sOcd{6DlfRpr#3zT3psn&i4?kn%>YHC7~0KtmQN_}T?eVDr( zWuXM20)*I&qHOc%%#X=mhj+v@eD3T#O2D24^X$aOSDcM@1d5r9wK>a0HQ3=Y@K}&2 z)z7nR`7)UAd!h$I5M(uu_Fn;MrwZCZAT>vB=a2UP{j%8+I;CfYMeFEHLR5?%U@5c< z%9T0))ia~DxuF}$33Aq=FRoS!fFApQ58T{_Zwcaz@Z#1%_p}#osBpTYG_(7DQL5Ru7AAXbqoe;hdvtW#2d%SpAhX2!WQ;FD-(Aa?vwOtUxr?~DIv z-i@T(T$n!YkY?1*a6R~~AP{qqkChZF75GU4EOXM-$_n%pWA8elBWy!52dhO+EjY~S zZ{FvjCJ-|{)u*xayS?Qt6^XQk4tlSDCzq%xVKj0iq-lJ}Kz=XnDG~jg3uTYYC~BMlLp8d6E1db}T7>TsC@oCh2>B zlvT^p>QQz^;SnpZhJo3SOW%*+M2RdT-K>^vS84SH6_bBWE?xXZ1XIM7!lI&eB!j1* zw^Z8qo7874;OH`m#1iBAnS#J*0GrsYWso4C34@mQpFb4%_N9l|0&x7q46Lo%0XOUzzf9 z`?>P0uJDoXZdo3drzIsDd*;$|B?wZF;6O5v1_;Fz#Q+7)(O1}Vh<6JC7LbpGjZcJf z_k2J-!6DUORPxz5(>G-vLqq^1egH8Fc?~j>4Nv4=oi?*W6Ztu#<)sn6-GU~2BM?A9 zpChsxU%zI+3hXZjt0sx!06->|ZU>cqJ@bScX?uFM>!Q(_8-m(6equDKiN<$?J^Xx9 z7fH)N3RZU70(N)3n% zsAi+m9%2k?l>^2=+8w5?a$(sc!j@KyKn+a=!;Vl10sWAd5-BQEqlcLo6mIVRbUCkG zc{20OMe{4n9mlzx1I6#W(`@agRZ*5EpRV>@GT>yYWrs9_Qy)UI>Dy(ue6-&t@A~Bx z&f+EtA&yDj!XcgVH5LcMYSXgQBqJG~oZ9?g2#UL=fr#^$(x>0qynN!Mm>4+9hUTP? zumh|030JKKv0eW1t$p!`$~}d{fu{X$Utf5FD1cE;bPSnHs2v6EeOCl{qeH|039-RS zZB4PxIe+ky2KTyckG(7Q^VNj!c-cJQrmz$^-fil!vps&}RG^&`U9^7>eK1ALK;&G^ zo)a$T`Xd_)XfkBlrlH**MC8ctL~?lR?X)8In8s`qXJ4u<-`I0ke@tp?THZE`jxo%XMyj5=nu94R!Z>+9QvtbdL!!fqX%m{0kS-%=|svb-ssHJtGc z^e?CV0=JI}u(p1_x+j>?AZIAApz3H|+fm_IbxCdwrIb)SQ&=t3x@n*L6V4Q6{q&C9 z+}yYJMSw#fI78~=4AVY*Yx^0Lmow+J5pt*#3ML$p^}@^{3`p!mKd@}T$u~X;V-Al; zmC#%`2!br?S~M>uovK^Ozg*tI zumIZY(HUDC8+zB0o#)S=*C)s4?*lS4bH{vOpMkg zUDR_1A0Gc)K_+M))*BErKd+Q_?jJ zSZK5_u07@C$}Y9&d zc{;rI!>dNC+ZU@AHXuC{;wGNQ&Cf5&S~|SAxOi@9L`u+o7UxO5wl6~6T<78fPOpeu zUiOEuD}!!Ey~yXmc>!9JSxFa?I-QI4r4pPRB;$3O>HRo7 zKT@fwxz9w8ZzbyM_{31ddQhug+QQRk&t3<0?o?1dZ6%i#L?a!rr)It!(eTH3Ppz+# zPtg;Po}QXwj}cTmR&0i1@-Z>aqmtaUU%v1iwruxuwjZ5abO+Mcu^RENz!o)xVhufI zqNh5>Qz;tx{8P{>oBvY%jucH{`s9zt9HRCdKYA#+9_pV)rHpb4>lat~_@M1H{}(k= zrrVdRriNbCYd$>08;wq3r_?vCceah*#>Cj`T`>*u!GJ1DCL26C727ySw9`g5fmef< z`tF=mJtE0n@rh>fD42D_I!@;GD!#v%+MKzFCWp3oYS5D(av0_zB)SN%MsH6GGZgmqc0Jk{g5JdT!n`vTmCbO z-jALBm5t8*%U}D-Pc@=uUTLWXwcJ|z8a9Qc4rRn`IT&DDMOl52GHF?m@O=>!;ATt= z?sX+=XiG$4N=gf+^fSrSq?Yu)e|%2XU3t;buUOkRW!%{avByo}k-%|Vn-4=9tM|IX zf+k1^;Fv&D3x0$sv9zSpKRut*K&c;c;e9lJky6hP({SBdnkkj4b*>+sV9}uZ>-Las z)yb?DkM^wzjUl?CQ0%hlJu152oRtZBcQ#!hIeqGN$AT2IC3qL85$=ApF9d$W5FR;P z0=fnaGw-L${7Ez3qHvu!^W))iy`hOc$I~NkrYpqUn|#$s>q`%u9HX(5bnCX?CP?-^{_{+ckU0CyJ|8!)=g0tqATi%g1icQ(L=K*>FuMH zwDwp6(ha0)Rmo=HX!P!sh+l=Nz=+zs^ z=(J3{e7QAg89Ck}kIpF2N2i%KHv zd0Aw=zhS%A@r8`YV%69pq_|6Ee3;wp5t@XujbdrazEPePS=KVK#Qa=|{pKXE zUcD@jL7lo)o`Q@_13(j&&(Hk;FPE9l*vEBtGG$Av{pKSdxhs=XCRcy--diU(YZ=Zr z3PlO1SfaKXfYVrFeL|zxh*XHeBb76uXHdZaUqP()O!y}8mHb=WzGQKI;e`WLdnclx zah4l>!@OV(L$n;GyC||1TdR0Vmp429TjOAG_r8UTia^GxJR20BFs}lt1!J`ty(^Ym zOCzo?ZT~pe=cY~bS4#O5#vZenT-f2lwBh>mc}Z>x6C*>M&ff3OJ6s+c+Zd$nXJ-O& z$uO59ZiOkD^w^+zy}Lt2%P<`smqtH-Xu@FM;<74I6uK3`!&)ZsDHsPPxCEn@cWl9^ zQs%Cd3mUsvX%y${z;fmJMr~TGJXLD#yS-cO3-;jAP`qd6{wQVs6{M!AcdV(@g|Z|C33 z0l*yZr+8VzWP28uSIQPvq?$r$SsSk&!1j#-s(#_5&h7Gh1 z)O#0W57DTvzYtX^!oAYp^kAM2L*-W`=8H~d@W6mwxiu-n0JRlo zhWlu%L&@kpAU^OBe4nABTQ7&{^mJ|ikPL6MK4S4ldvq;Fgyt<>Q7grs`slEZg|EY& zXqDS_k?C#^XG8Dn?cEx|*g1aa<1kPd1R`fWoOPuus^QT&?1?d$)-p_(&=&jz2oY}0 zCUhe=7h?)Mt#!`eIcs0YXk+AMG+3EAD@qX%UDp$42b8vUr|9kGW3~FcYWPKSEB)s& z)2*?=NPUiDd+%)G+Sy09BTx#Db* zDYU_LXl~T`{k9LlGNK~D=BL^de|}=c$T8{Io^Pb`iiUxpmSL5)1U>e6{)U0+5Sm3? z=Jo+q-e~Khj{GsdNlzuh26$)hNobzKF9%V|CD+}TQ@%(h*CVaa)2XJiRa(Y0dF^D` zfJ&_pCv$U?iO5z(uL(JU7>I?b$&*C=zM^MxHH8CAe?x(A0JE~ahUB24IDI%ORk7?4*c|XujM*e>OHbzreTV(4H zgIx1P2L-+dqp`cO#hBUt&*R>RN%PAqY=_hZST;O2LE!@=%a{QY1}>~Oi8zXv%g z$2ijPm`533ca#_>vuqYW>qgr`o{vt28BiW<3Qb^K)5+Wly5H-j@Z;8^kIG}ZkK^7} z9YVeeeCge;Ev1y(eGUy4ockp>ncoi42p1M&Co3x}p)sZ6qc~_+5 zpGmiB#%)~aV(rZ&;z1e3`E?&{wW<#p9V?~SR~HRfig6M`kMj*lZ+cDBm5zfPWcib5 z!;&ud@lH9$>qqW=w3l!MZ*V!Z6F3(0ns_`$QoSoq zjK+dSV46i8%P<;{GQ<{n`z&aeFJE@Lxq*RRf$!$#i@o7GkJDqHz5NGuYERXXA3vBN zfC7$M7R>21%}x76LF>S|X&8DcK2vm&>93rNKXur;8?n%JOCCzpMf=lPRym+Z`TWio z$dbjyq$gWWojL_T^kYLPbx1>G>k-w|1|O9-7!E%dR8Sh6apN3nsq?$6z-O*|!vg!C zLHbR{>0Q0ObeJ?yyJd$fx}|34=7#$Rr+uX5<-@>J_yh#f^~Df5jV>NY>zPEh0dqmx zvGNgG))4*Ox@E&UoITf%lMltXDRCPQe9}P~3QYt+_5J(zTY6c2-W42_`lr>^F%XBx z#>dl4B>R&uR;8_12fzpF0Fy^x$Zrj+r;;8OL0Cli8k?MiuQDWQ@xlHuiyUL34#>yP z-<&9Z65r&(gms8??`ukapk zEvwCYd@8SRxFt(=f;f4vyZf;GM2;~tL}~)i5_1sJFoGijJKhv8qSP+p8?dk(P;RHn z$LfCRQt;8VYnX#*QNxFax*Fb|m02s&qUw|Ve3kstNmiM-u~N!y{) zW=H+=JCDeY6?eGcH_+|IPX7VU4PM&C!(tdzfCBUC5_Of4PN~AK*lZdlBRB{Kb+W43 zo#lwJ6S#6e|1aAwUKS04D^nYJ=YY5YTYXe+!l(k`=yHfM?V}r*FZMn}O>68GzkmSY z@c=B8?IDe1JG zw=b1V5#E9e7t+vJ7!`5(=aES9>+*k-j<7f16^qrjc5>Q;u^xy`<$jp$_Rb8P$+N0# zSy-_NcvdubR8|2f0(EBMY9IA1!GCQW9Kr+yBQ(L6`aG2iF_g@uw1%{hE$H+;>|?#< z)zpZx^ABlGISD$tohrvQj~K^quVITXeU+fIN9D>-#siiw6=n`wwC6~^n12}2FaT`u ztLDK+d+|MhX@B&eYi}O#zB#LQ)iiC9XM|2%J z5VG<2=L+X{8-|153CA))MiOu9bd)`M_Z-5^qZTJ9=~%^qI!+k#RGsZX!l9Q6&qI#) z=F_oa_PgKUJkfvYmpa_7pjXydtE;AFJ=D9OC!Rnkmd`(<^4I6a^X}|cBol;L-X(4d ziD-Zx|GDlQ?#*x?BE%3?4V>$W8NM;A<;pp#IQ8b$OvAKpu7eXuoruYC0bSsRImTcp z`f#i`%F@Ko!CZoufN&*fh?peKk4P!eA2jD!O4Hyx!LH-a_tIgJp3|19lK8U=%wQ z0b&bPyv6oI;#6)y{JIr+EJHi1MYcz+)qQSpx%3K66p09miJX&Q z^s(nSM>qwt2|>7DS{~qIZOBpF-y{^ycA;5oDxDx7=rnpdJQ94yV3^$c2#Vni1I9{= zxj%hW5N+Zvswq$4Er&gmnqI!>x*)+SZ064dTgBj|n$a2IMBPse5`3&iTpt$}7K|z> znrYh$DZ3)qnUjkK0OL?IIT>An#RBPKaa_oVu%3xsIRC;c`UiE7t7`bA!6F*UZFn1) z^lu#9g=iX0OrorXiD{pF^QY2{=xG#AM z3|=zWHcAPf)42aGs$pPz(;R{rL2LY~_9;#rN{*J`3q%DNW8wL!mp|r|@4OSb^G@Fk zX32U~@OB;F`ovUoIG~x)(zyBl@)Fl5f1wefj6-yVn+aH{x4VMnW~R7&kIm#QZ8FF3 znf}_rbPFDXhz8q2{rnf&9*Iw^#U^AU*!U^+uTRKR*_D;jZN9lkq*%-HI`xSpMN%5C zE2xRR|7)~7!1+tPg-Ng9Cdb*s2G285VC{3$k1sB=6V3IFKDHY^w$n|QIiCB!g;r!* z)K=DXDCNQUlif}BdZKsQo16^HR>wX^_H*01tMEquaESP{YD@1Hzs@mMZ&_nN_3D;( z*=T{i0)Hv17Ljh+|LsCq@lL;0FIm{-HoLsc{>H-Zfo1Di{}%~y+85QX?&pY+Oa3VP z)gk#M<P~r)4 z%CchroX&Gfjq5yC@48zk4^3uY6oj8{)za%vD(f=?1xn(hcVeLr} zMS%JNQ!)7f{GXaV0U*02GVHH*_zln1As?-^$DFi4nS|I4zh7--Ky9kGW*s(!R&SC0 zQNB`@ig&Ht&X>LRUX>_a6EL5!ULpSy5U>GyACH}&`=voLCxbX9TKoV+4bcFNEzNiKyhlfQN z6YaJL5DVca;N5~Z6H3$-Mxs_qfh>YDMK9DnXqqUC-AhdkYad-thZA!lmEuCi!t|_h zIh0{pKwO~MKrE3d2#k`AP-YQ%aRElC^(6n?M$RJ>>WHyK&A4|hroA)|^6$|WS=5 z3F(ll0oH*Iz(YBhLo63xdRjDKDN#YYMxlu&?t<4v+UYh$AswnA%LV|I-b-cHGSfdp z56(6=oR)dRQ;`lC8oPa?*?=e49E*5wd?0cOXf`fbfekos)Y|y1EDS+%Cf>@qumX5Q zZDl$JXa&-Pn*!f253qmahot~Dgk$tT)$;5azs2zqeKHq1pPRD&kA?x48+3g_feF6= z>;MM>;Z#{y-4laY3T$RB6;{16Qvjo)>I$ru{2()UX*#IUgu!W`dS$eFYB0g-_2gWw zYY7gK*bWF!EJKq@$mp#_--0-EG82wZi1i5)`Zy+cen45ScEjIb>v5P9)rz3eu?nEt^3pxULo^U}4uwne-R{$c&pOuxAj%FHyZr^Ab z_8YDDhXz?wLl0VpQIDSl$HaJtTd&@>1|5%Y;kSS<=>EMKBXS&73M^}$@~uQB#`{29 z!CE7TC`5G*SXTB#M!PrW8=yJ?>2O?w_j^1oN&&b(D;pam`<&a>;8rktI+n1}v20j} zJ|5pt^=>p(SCm+~F}H}81suC5XK#BNYdeS`Z0)n0a|2dqZ~(%C5PeJ`MGyIqw+qwy z4`KCFWjoP=Of)Q4l>-i8UldVWtAV}odxTS!W6djX7aYIlO3@Y0~CKP0F9lworeo$pVxY4`` z(+*J<;zSJlyb%d44Nf8z0mvo;Sh4ZcL=qE^Kylc!KQnLek|GG0$&>#CEANPKk7Gn5 zE?~h_`tt^S1hFm;9Em_%0gGKduZKNfyOw0YkBZ0S93$500-P3_M12~89EFuInS*d7 zpyYxG07**w_6@u@9up#vZzU^aVQmqHlCCXKYGLbua)pQk<4GT|l0IihFljAy$7+k9 z*?JsZ*x1;nLGAbfVlT>_LYPSPpWUIl{L2XJ{hsb)L6-j*Ij*6~f%ii55qctm8iI&- z5$JnnaFzJM?GO?O?WE9zFz#bm#x$&>;}nyKWJvxP3ZhiwiMj*^KXFqOukl!aI8eBF6a|_eR**-@7lK*_ceix&w?|4EpruA2BOe5STEs5hD|IHxMR9ObFQ%*K>0b zc|L#nQisnVpr#NXD{x!iw{L`j9D*3A7R;*XK>$4O3jW(7g!fXK2g!?YbvVl*+{3YC zVBO|gVjvNZ6;J3DjLh_AG0Y?kJ3L3G;StO>OeVb+&~N@`tF;`{U=V{&G&5TSRNn5Zl8sU{qCl1corjMxD6{b|=Yfp2_N zkdot8vc;IuQ-(R5XH5xt2sBjoM8%XMrU|0bXO}|=Y0z7CB{YJB>32T*+??FaaW1Mb z@7g*!fD^iKYnaAsz-X?BVFDJKKq!V4g#M+9!{gkMlg_d(MIE4ju(GPxOCmv3bRR2d z&k)iu-tVcv_gsUMQV+ol!+;?2Q0W|=B2c3Vid?XAG+t*ts4(g*(Amk2 zJ}RsQ?VHhjxDp!IV=_WsgY2=yhL?cUgsXpA;fw3s&i%jZ6Zex0@cHn*R+jMYgY$$s zd?A!@5- z!s;BG1F@(S)2s{;gE?RG-3rd2A^mNC{jQ&C491Ur(Qz*JZ4q@j>K{jE`eEV?O&2qc z)4Y4`e^z=x)gyd@@VFB8Ak({63udIWZ3aFXoZ4565JL#woYi9NIdFpE(7{ufsrE&Q zO~ny&hOirnZUaXVELN8Iv6v+2{qiq-xT45wNJ*97 zsm`P}+jA)SBbpCQiM)m^444H6{@rsvm6neT#gYGrJ?`U=X0=3=m6aIbp~nUR55@&X+vJFKhgky_J+ z%SBdn+3lYX#D9LGn`wv{VPauH!t8x=D#M#tbPV)@3p#*XnK|+F`HTc~A6xfRl>VB@ zm(|wwD;?c3?r%QW76Ks~PQxukXL{F3tDwyp+M%riA2OcN`|mCf|8p%N3L?l{@6Mu{ zx(-7)mAVm04fZ0qL7_8QwAek?IZ2dO2NKW z)iWxCC#Wwr744Y_{IHNqS$XieW=VW9^K<1T1wLRIptx2CSMM+b##sc4$aJiL)A1O` z!lCG6p4SoRF(e4O((VO$e&p(G?k}y_tvjQS;e%lS$k`JlrnXLvbQ3t(u zxIZM=NecVsz_mr=P>=oJJ!4t3TN&gS6KXD=9PxWmpqB4ocM%6H;7MkSMg< zA0CAVK=8p6#vK!1;lEyU4Z3!p8x!ir*CNC`!Fc3c1fq|{vHs4DgYBOM0T85~2!QcA zm2IWrtqmpnMSsTFBe>HRU_`)y8N|L8_(^Mfc}07WPH0I zYZzeQbGv~VUnhs-=VK5THtn$_oBh^pb78yxB zgaUm^s%3$eeLn@FrZ1vmjizw@q_MpXlyRlFSf9>V{fcd)cHU&-)M zS?Rp}t6*zP1F`oH(gZBZhBY@kLW&i(i5hN(U<)>z*-%E*Q;w8G&uXUbZUe4HW8-XmuYq z&KT@q*)ZMVkcy%Ss>mtcJ4r%gZVH%kg;iCod2Nw@q`8t6MceJo7?}|GP;f#SNy8JE zp`@!23ti62Y$|B~o8C(zJ{ZNW_EC~F&m#uG^c|>B9mBu1IcIk3Vq{h&u zu>rYGybyzPPO%Edd&B+}NCy`J0CLJL@|XELh+ zISgpGvu$hJyt!2SnT_Ibv?J5dW&gM#*_ahv1;&lIwB}lbD=m9h5kfTd3lqs!ma8u~ zo@ZP8czWId=8$Ndoc761e>5+THSeAlS#KKqP>#c@26Vdh~d zsc|}cAOQhT;u?v`B39UCq@aenKCCv#T3TEA=0%NmFTlt@j$(X)i}wI#XhI{&VF@G_ zuK+3mEQu?tMRCTb+3KXM%Jw5Z)jbW<(+9yy(JP<~#63Vb2=#{SLoYNV4Ah|pkD0Q|k1MNX6OuUMyQXjuET1I|{g4qsl22p81nEZCBtX&mVwg1adyT*z8e7^dc&>ags;3fclL7(5( z8_IFM>L4B&jA32f!xmOsGuV7!2ZW9_r3giy0O@!P&l+5iQJjmbG8_;#$0YNA1G|jf z2N}hlBV;oC;yG;pk^U$U5Z!=SyIre2D;reL*7n`f8N}+UU%r*?s$ZcMt0@DaR&=lY y?-wLQ&(C{mGw=WZB7d%Fk!ynG{}y5sS2xz(cF&T}^xsE^KgUUWn)yeqgZ~c_F%}d6 literal 0 HcmV?d00001 diff --git a/perception/multi_object_tracker/image/mussp_evaluation2.png b/perception/multi_object_tracker/image/mussp_evaluation2.png new file mode 100644 index 0000000000000000000000000000000000000000..91ed6d648d44918f690bcb2b93a79669b8d660b2 GIT binary patch literal 81846 zcmdqJWmuGJ)HZBjpdbb%B`P4&=+Fovq5{$k-QC?1Zcso{xsr@}bDitF_8WQGr^FYiE}S@Vf>`p|W5p9EPWPNR zaVqotS@@fUv~#8K8-e2^N#*nK<$2yH5dQnRlZ2X+lC6o8tG_Ny}d365ftIP1MQTMS|?;ZN%Kf^aI#;cjH@qZ704y2$L)A;wFy>dJG|NIYj^F;nh zLvayZ4{v#%qeLnphD4G|xcBBT{%agnl}H8#NnaF7nT1RXD}nhOcPMx@Q#Ycx`2OLa z0MS3)PjBcaGG&{m&#z+t8u!)Z5micm0oKzd&+se@Uh6>IuZ4HUzWYM zgbt^456@to?P<=np>;OQ3I9Eom??KU%q%GeQDmJ&&1duMt#{O8g+?<(`rx90I(e@} zj7r`HN>2LU<0<$!F=5!**-3dR0G2+^UmJ~$pg#!ufRf5pPS?nHSRQ`heK4=BlFmy4^ZzzJe&*R*^8cG3v`75?_;`>s=JPhc zWaPNpVb`m27W}#Nj`REM%|G=0{MS=$Um|2AG0|K^guXB7&p*RNGe|N#4`vlth`#lh z+W#N(#Q1FW--nfN>DiCB&`3>B(xFdzFRd$~3)g7>oTlY!W>ZW=fSC;DlQs1TZL9(k z`QM|*rzA0-KRgQ1e-_CwQyEq;U#QI}7q}d$yWZ;4p{fFAGFCTB++>j}{4Z7lSve%H z`qJz1CPif54NBKbWU4GMq-=iuAp22u=jtM%0_l|&ZusVZ(>&1toa0}MHMT_rkc@0~ zBl7!I6IEAM>DgnW=W%wHc_ISV`G5BtYT&Ri!V z_77V@;@YzAOa3t3yvxLj{~7Ol8+B+3NsoI56JgIdivsBxZEQCpls^o1{#arCmvdU& z|1ru9pEI8M_3^LZy=@~IU3CGv*sTJ##s77R%KzpDw}$EUxgwlHB$7uj8BZ>~WUX0a-x@7rJBvvBLT5ubWdNH?*8#1Z`U4`Fn&wSR>)V$?X`%{ zmZWLPH2>}vshcIyS- zmk^h94?G%MTM373;xHIYp>qtcOq6Dsjs1Kd``m`0*yYRqH|0`=$7V4(PE|vEk@aXT11d?HK4_`$$CpA?+NORY>xx7IvyL zMF{Le)bLItUolsC#-+-0we^nY=76cN=l0tGk{jePmfG0hgt6u7wMz|Smq)fBI#u$V z^*y7@h5x6Fj0>dVxYN1>1O&$Z{CPVxq)pT?3JJ2jAQ*-EfYNwnfJ6@b`jw8Ey)1DB z@{{MzRGdWC?r_bE<2cMTm%>M+Z1F(mfK`tf;uG8aSAp_^wqL)fVvUPxYdgPxzffvT zfg^9>e(~Z3tQH|N(Hu%m>Awhu;b19jjXx~-aw-F1i3agtZU5U2 zdzwBhR$WJDI>mK(Y;$oiy3M$Gg1cett?1!O`2I?`&tzUi_+FvM*orr$xzlb?xpP zYc}TYojZ4uQ&O%Fh$+yD3K3Hn34rQTW-Yijt04akBV$v16 z{0_xZS&+djb;Uvk(}<8k$eczWwC%KnP3TdcP0ZG(JZn$mgL9v)44dFLOMFtH#qrgZ zro}Dw>16^5rF-`7|LY~={LNbj7sUjZlT!lpzC9{Jp(wsO(`8~15=bOb12d`(mlQqa z6RVoLhCSd&%qEMm#yWEoot97tS|j!y{krp}?dHGuB#`fS7~w(zv7oX zT0U2MLiG9ew%xbxABJ2Pg9dMGWJj~7EcG9SJ@paIE-E2^%g;DEx4y1q%}Ng+Kl;%h{H{xlx2kS}hkf z9G7^05J)ejGiUkA{_C(_=hzR!$=6MbLPLaN(Vs9$wLh_^nFj?6vM?M;zcZxrjo#H{ z5~;Jqn3ZU>;~d%ASbUx8MsN)zqDJoS2`YI_Jv~?R^71|w7Ah5DbFuT~1=2YfeOPC= zStEX(bi!^A^Lo>VY%sG<;8Di#q26Ak)nKiB_aTP@DR;ti{s#}(eVuBPf1^JZBHNp$ z{!g*&ym(EvStR_0(%Isd^=yqktzv?*if7jfMYmS^Tf(n~J>?Yj_$hVPx#i16X)6Sc zj!DE&skM`K%a&JPUthV)B9&kLiLSMH*_@`2Gh=q&1_rL@#Tx5CgT#7@M-YacvZ+RLVwN?Cj!t&BnVo}!qEm0Dkn=gQFT=xh0RaI{Robwy3a>rh z!NEZ%!IW_tlj7?&I^o`RU3UDF-5F2&OSPQ{}HRe$B~)szWjr?Y3mjq^xT!(Q%X(lr0h&x zj2JeHF7Iv5tWVKKs{l8LzGvDcg8sI`OdC=_`{VGn}6(gdQQc%ac)+ew@A ziPpxR*Ci5?f#1Iy?P($z?jHWOr-8B-BlX&$qJ3qBJEJ?Wp+Ou<7Nj+b&U!Q(Rp?o2 zYHBui_HK)kAS?zE3U+f?o0b7*`Os@|PjvSw!~aCJR*BJ{K8M$#{^F!}0Bc0n{w^5O zp-bDwtgfcc%#zL(cMeYvHGUM z5mx~|48irg=0)7%qIF`23AZ5Y^7bNsnA7}W1e`NPCg%<{>KKZ;ZCHsn@N$$zt^Ew= zr`r`?kfrQQLuSUY@($9*x%OGa?e21F;=2fkF`OY1X-^XXx#PFVAg^TPs5@Qw4bkbz z$yd-A7~QL16Gq51pg&$LPRFeYq{yCY;Bxyjda`&R1e}=CA52+l{e9}5zrG#h{-u$+ zuAZKrDWBExBe0(E?d$*cZ7#tl!;Qa1%Z`qe!XwD&#oCLG`-cS|^#N-!r zQ=c=@(9(9#I&sOYJ$ie|_Z?-5v&b{);!kfq@xIc0r`AScL!CW5hTvb4}t(?J|X9`rd&^WdTKK3;muzId*!enruK_o_)s!=(v#tiEzhk~Iu@Vm<2|<&XZNIgoZ8K6UlhN(glvc7W z4QF(s(LCrz^K-vIX300>(HRjf8A}A%o)2-)HH@P)THhJW&Y;55QP2GUf?eBmgv^_X z_*tj#6D{F8Ga2FMeNVhQ-x!om>i8amz-Lcz+H@2P9+n*L;P6<)h_+|Vcx1=WNgL|% zT5;Mz2n65{ixQow95#Gkbn;>3qsuvN`XM(M2^6GU7uL!}C6M~L2KP6lKev(BT1IBx z^)E=j%aWMrbzgz(jKuqGp00kyqQC1=MP4RY-}AzkZODoGlvn-rxh4=N=_fmI{pp{TxvP1WOtb5fbW4$wmQq8}>WC$Oc9@~r zj0SJm!^4W>EE|~DjAldivRGPLzS0kz;D<7g&#zj_nZylWO08L9E@*0MItkMDAf{@z zhBGws$M-~1aaSa+KrRW$HV0r-T3V{6shOde3w=^zHaJkZ>#|Pwh9(lJqN>WdP)uGJ z3oD!y(`aRBmkL5Lx9`WhbK&$x-+y>__d+GgV0M6RR<6-b|Bs((yAuhzJldFJiG#Lp5o23DgOb8#hm_7rsfwa0`yl-C%| zyW_36E}oxw^@hTp_u`D4CslzYrs#vvlT9`0mV4+?YYUdx0{uA_|7=p3HY39FW8S4V zC-*`Jy0t_0I@Xi?e&1Zy#kx9{RpWkteXaPD2XVVMdneY2I~wO_=V~&VvgDCxl$45y ziN%$QFwt2-O&zici&^(F+`s9Ob0t0vsd-yO!A)Yg&!s=Tx1N1cZukCzgsW}KPk<05 zkzyrA@|rZnrrn>ciiEXPLz@ogR1e7hw$7rj3RtWVQZuNpjp0FqswiIP7Pr@?OpR@K z#57I}9GZ!%GADHTf6=w9*!ST}++WP+y>mO7cN`KLoW{vd~3Z6DDNbs^^ON`A$uWSBgM^>l+%+$uDGn-kI zhF72{qlr>f1{gw=()n)&Ui->lPjc;v&Nn?e2SMT)8PDA)06BYZ3lhm4x3axM3Ruj7 z53sSR?2NV*OdV*+HXe1d#SS$MQ&EDD;2-K!5V_ZjVKmYd^EldwYzZvIPvVZc8{KYI;o5YMd2k?dIVfL= z^SUy5+t)nC6x6{-q4IS4wz_|Lzc^Xg$nfg-!ffW~=P{9lBR@57johJSoK4qHXjw@& zA2`(O?B=r6=}X&vPX6NK+KOi-N?zM(XDOPUmx?hqPkjO%gX*vtVmc$0?H}Zu{_TR@ zzb2ZBq-W$#giRa%hF8SC5DWBcz5NT4Cm5|lVe zd$7{SBhj{PR&`OR6l2j%|w=(#mJmRCdoEs&&Efy zhf1|F3kF!C6g@wpE+nRt#;omE|9g1j?y9`ca`3$|)Z>-eoU~Q=MJ~3z-))94<4uBG z3}v8mcULed{c;PpU;Rty)>nH~b-5{tVA)(mMQj(_&}zE6IA|4rS32jNpSW7U5sqSs ze$GDsEk94$+Aj;$(Hq}p&b(gt_|y)Qg{38QMMW!E7ho1uC_g{H9)jwuWGE1$_yaBHCtw7gJy~TDAb82 zx|uGKy%0IkgJ|f-!otIWoYCh^vUhT7?C!n-*z-w7J=hpqpqp|Dp?)yP)$xE=~)TZ5`)!l93 zkXe~iU;7Q0pEvznd-ringK9&uFPUw`QQP%76`teE6*$XyS{WIW(0iQra7|Z;QooL+ z={xK%Z1$$r&%FTJmU>F+oVkR88G;H(`O>m7;0N&hZHe0MqB|X)wSpE3I!ReMIe`Zc zrdB3eAS}izIXX@(mZ{w2jTSYQ4#^y)8edcGgP^O5?z$exO<^A z73trgfa3BW#V;AuY$83P7Fu-J>0ZPx}te?Qq5Y zq!O^T> z+L*`U`&Ac)jFO_QH zslwa~jN;--#lh^ok@Zsfjg7%UD;n-if=364zy$WMt`{05rEC}OCq7+R&yLQwdg7e* z+3a~KKMLn#3y+}1em7Cg3%2{0iZ=%G5L#T!qRVm1Uvuk6DoGy1OK2!@fp(Su1V4Y6 zcq9YS+0)RrK{Jl;$|#9Atm0%aFdCV45`=^n8y9C@q5;PbO=kb#V8-BL&+^vn)}Dm^ z{Vt;ucvhsKpl8+zT;!((4?jX6S>_^I5JWs0x&o#r$mZ+6pH z3~57ee7vet>I7{_3`)kd`{PHYQZ>}CcQ4cSP6|1?%oT%*XZJG-*<*z0;8*rB7TSh-8wp=OU;VIb`q)yamFFMR#qxjo# zCPB-Bcq#%!G?4I6Sg!fsgogVa^S$XaO&&EmM#;Z{FanMo&vGZHrb6Sl=u)NTopMfp zuryaC52j1Pwu#x>wOwWi;F2yAoIC+tsu_YyCJH~20`d#2dy`1qYS6^ooKU;VUVuUG zi4UD&xi`2siVu3!83$VglMJr|^*KRF6_%w?LP7jp3g03CYPTzXVqz@a!i#WPo6`;b z3pGVknS=iF(GXntdIl`i!LIYt?+QO-b%{~phPPZqP<|l_XR+tt-|=U~~VtL27IJ4|k1A<)-C##h(S!1J0`yuqD=JE=I~ zXE-PAr&wpA271Y>(`y3yl-?7~2ewhm0+1UfU~Md6THa@%5~nkJyvLD?w!h9cW{k0z zP0ITt7R|OP_cS>K?QeX}4-i85MAPrNZsv+D3R9(Kam5L}(qzFU z8gH^t5)ItBu}&=8yi?qXtM;?^^{93^ObcXE7o@1S}u?88zWamt?{+J^1?(ure~}{UpF^-kN%Jx zeaY7>3u2|;K?iuA-X9nkcs+G44ybvJd~$mlC5||CP0a})SDVtdJRXSb&fKou9={0b z;;{Y=HURa~_ycp0tYXn8qR^oHViivARkXc^pSqjA$;Qq=?*(-X8e{&2?VDhr=xo=A zenGMq-5=X|?VvjJ*tIW|?oUJ}bQG(Qy~ciUuRJ!Y+#@=@rx{n|(nO|!oCCBn!LJtE z((fKejnAtx7mNLw#00jE^K{Zz3rknd!VhQuK z68eJ{(Zh(5{b|1a3DLvb{`x;47!Rf0-}2(gz|JZC4bMAE5D>SQdoxii{`#a{5x6|z zkUW&edQ=Z$@u*!9=0=0O@B=Xoh3Jc7yC_^5-ip8!hd#+D|9X|+B=C$tZgJ6tC&>W*m_C+3@G3(ocf#e3!pS&DBIbJz2?U;?6>G{vNI1C{>HM7xbVw4Wm= z3RD3r8CFaidZ}k-p%{y<0Q_Vz3?CED(+RI(o~NWU4Q(?KYX?GQ^O0=M$)O@ipQ}F{ z($36gTN+%a+Pw9{^l53`;19Hk@h<~)woFpxmeKH=$)Z(WE*BcSxY|Yz`uun3`nL;}z5zQ4_#inI6hYzO znrVnq4@kD23{C;ZKbRuDeWL&p!HUu(@%t@CqAm18+D>}!R!!Q86CS$t1J~lyM5+!Z zqZYa<(`tWX{Y=LO%pdLXA`1LWYJbK(izMh;18K}>4R&5$-ebN`*=K8OYiAuJw=l96_B0zOAu zKE-8aPhkYDk_Y{@nz}j+5h>P^@_H>IqJaElWn~3ieV^viPKT{`L)zhbPCEa96)(V6 zSjn$N-V|A!KGmp>A z1lH?4q-l}htMnXjuH6w0N>5L65xFECs~e0XlW9{vqXZq-3Eky~GXdNf`az)@SKbM; zNqgaS0V?-}vJKS%9!my2>eK$s`?;ydHfk!U<4J>lmPxT<@tbi{WGhP# zW5E(%I*!MOVkJO_1ep7|F%v5&H&9NL$*6;glj|D(e=6$p`LXm>D z9-J;b+AZ9vs@oGv74gE`SJ!hzqWfjJG7AvGACy@*Jw@EJDuC|hh=XanPGJkom5$a# zkHjIv0#ggUH2{)^P-?y)Cc_eq{BM!~zh<2vjg14I^W0x)0cZvkdRntC1qxRG%|#8#>6}RCOSRxM#;qQ({l?90IeC>8+KxckI$Ro$flx!ig z)uGoUZ#V<`*NJc#U~x&eC{s?aA271m{gP2_TIXfPU( z>!cEQV?A-SHM&1{nDnrPx;WdTOo5i)n6drjE)jaC*DxRR>U4@gHG^$+e6%)|+5&mns<;r}I{j1c;CGo7mctXycm* zSTW3Wp<#hh2T_BbrDZT^+@5F&ToDzKX=UlFM7_&n;c1}Ttzjc~+7h2;HW3lM@&ObTZ`y7rz`!fNqdxu3>ASYX*@} z*@$-%2BQR>Az(2WMgb)C@kz5OYlBJr#0n)6sjjQrf@T9_0+R;QPBM2WO5AkeATER! z0u5<{(jQOJK~p*GwFTOjZH>3XFy@7afMiJIU|q>-kYiWYS&$ZwadmY~4GlA9l$?9D zTf1(_C;=A+z$a-Bx8~k$E(?8q$3Bz~SP4P~;5fVvvIcXE6!ZuNhF+BZW{J&uT*sqg zkM%&9m{(|J1AkLmx=FE2czIkHiIi7(*tV%4$|(vBlz*|AvI?&{%Ba3l#T1$hIK3+InyRLw|PA{k(Wq2m1R}8 zE^UEu(HZuH;3vBuyCzRWI+4?PZV|@&Y<`__1~~PvTV5c4Fu9AXHP8IHqu#gE;x3_q zLBz(!!YFLJR<3R&XK<1HpY84Kc)&E!0YEZ`7E_TUj+@929Ir%!J=VSu0+=c^2nRvE zu((JT-ho4E#x^xKp9MTf(aFuJJe|N6Hj!STo`b;)2=K9xm6df-yS@<3N}ajp)ec+) z0FqC|#g6(XJcb!OMPB&Kxa=pfjsyNWMiGbCa>79`pm;@vM_yK@(`Z{X8h z$)>kU0U@`0=l2gN{;>)x5$o*(j*M*Zi+20RQsPj)(Y-`GSWY!XzH`2R@kd0Q^NP2~ zpF{ZwlBXo-@H;JCHnu~)y<6{UH#)-iZaPsru~zZR>wFh$cJt6LOt|KfG% zjT4oPocwAynk4Sz{i3#Kb8sn&PoqGYg*oUExDICaQ)%fF5SDhEaV2%gBV(X>g_iBS zZ*b`JDyjm70?r2LO_-7bi*xDHrR{~{uI>FbywVHEL~XZ^6a1k1fMgDqz-s{{Ozk0D zG&BrgQg2cWx>MWdBe|^CGyef7DCe_#?Px>y=!|fcMbr(LGd2|gVFw2llnzNJMk=dZ z(GeIePmw$4eaC~kp~o@jO~SLm{9$V;86RJ5-y}UlB=g>YIyyg^GzysDo+iE@q`u5| zD}B;JghAJW=YkE>qKf2f7ce*Wo*%@+fEWWcFg8}x|A}SM`ioqHBIOcwl*Y$iDK_M_ zt1XX_=$$_EpjUX^=D3Vu?0fh7^A;)D4?PGc3eh!n&-X5;CEfpBdnU<;xNW%_u*gCH zxkM{VH|o;&DTH2!_^NBDo#2h^y1RBbujJL+b?jT#VgjJhMD8YmoUKBu*?DN(yLK5G zEc3EKkalF6dAQ8?<=YbVz+}*^8s`pBfKJr=c_DTJy6ks@i{9+dK#-B8sBdWKr@KE+ zf!8U>;?!IEJ#Xxkd1)7*z?5CfN}z9<27J>*!#Dah>3-cQbZKdGPmf|z<0A|LFP@q8 z2H)NB)NvXpK2{v#6>Wc0=Zp;UQ;3yZaaJCJCaT2a zuB8_Fo$cUJVPXUS;*ZzdY{wld&kwjapbrtFb~9HP@AjpetJ5X2mZmNiy2vDkN#?A6 zbXRX^omQDo{CC2)eRFlrc6exaVIgG9E^v8|LGr5=uOSyDpb(I086&91+;y&GuF)yD zzXi~Obq;<)L>o1_?hZU<5!Oj-a!vBV6=o9K)F zj5%PLRMnzssrckH%9&-Z(aol3ZM}H4QyxUQ$Y{1N-kKORf>Ba&TEFiV47UL}I^Cfg zDuPj!p#`0v1O}}hkIbK7kWhH2O7>hkqryz3k0t5jbL(HmQ7$l#FEtZ98~a{=9sumS zJPPWVT$G~nM@PkqV?9IpH?9x^B4pi&sbC6lwIKSM24!ovnKHrbtdkU}L{sFv@bjk% zk1rFz86#9Ww*Jp4ORD_^Vpf!LH`19w}2M^V}-fk8l4&8taZtAToWwqmI>0$Kl)jH;ksqo%R3EiqcAI`GZWNAm%r?oaI(fh^Ok zbmYAV!`hl6xz?Y|nu1eJimUq*R^}B7`?Xf{<=J7@X8ryjhw=IK)i!U~1YS%45>qHH z43Z!lVwAxLC6SRRmX?MF7(jrbY7t3%$guQ4XqWNIHX$L_SXG>KYZSx#!9@oTkD&R= zj~_pNDk*6KCJY)^&>4f^48*qP3YqO?#nTV6j^%HLiA*q|p>tgx&Kj_){lz(K33KMl zwwIA7m6W=b&$RsfAavF~lKg3OrdzPoI;f7Q+}E22-13L}ac&FtydBeOUB2aJZrQo& z8w1+HrVZTYG3+Xqyo+dwoJd-8fxKkRN*3a_V`NziG#o%&puRgB0!V`KidYb70BN4s z!35$t`tu(^Xy}5eW})@J3H49d?axb~FUiKJm`k$~v)`B}!n7_bCWZ{~%#gwSydD>x z&La`szYOX>yxd&b%CSS0OeGJwG+fg*ROMRXJWrmlGLQ70)u9GGuA8{9C2vG1W|vn# z`SN2zZ&D@p>uktJpgJs8=dBaeB^TKg#}A0x!pUXYdZM8+Hi;;SjyqAw7dg+#mIhRg z#W%UJ56TBeXh5{>8;TPNX8suQ=?UOHdf#R^jb(v0|(g7seAWQo@9szOa?1qPgcoAqpYjo}qiGw)%`lSGT ztpU6>R%vtPt*WXjWTXC48B&Q?`hDyVYzr1DIpAnJI%M$T8|dR7mCjcJdbWf67%)KY zb`!8=jy*T0k>9*HScadU0qi{1KjS4m!_}>xBAiQuvra&SK0T`PAOkhl%C!uZ3)!h> z21?WAi--itE{e7bdEHUR+!Hn7x=6{97)@+))6e}&dw4uY?CY)Uff)knu2X2sIsV{^ z-i=7HJS*VW(u0PaWab!8xAbt!|L_i3dVdUqN5pHNSAukDscQM}v;>+QopN0|#M(gv zZtGT>Pbw%zq1k~d;Zf5G1T}1Iu*?<`A>1Ws5;23DDr|W(KNj~ypr61aP?i{&fip-3 z33LFhUCy3^vgmHAQq0AZLxfM$E3Iwre+(VTY1nUv5>)W9{PxM z@$pF3LOTHS&^;ZTS|PR$J3)VO8N{iq(F~cs zX~=1?V0^oj$-9v)FyTyB>^}kcMliYal!^Xx+pB*XlNB7%#v|^2=%D9w65ZRlJg zTu;tl2A(mwdHj7%wv0Q6(+GenpxB~pf3zuUN)sv!>bIx2ZHpGD_nGxUZ8VXV-1+Bg z{Fw0Mum%tHY?g^kyVh~0eC1YxS4MJ#roZK3DJFJ8N?=KWb?wM*=ntmsJS`$hwKmWl ze^8%nR&=DHN>)Kx(>oo`3~!>+JQ4<`i6+ zE#Zn_6$`N`BmNaJ?{hz>sK{^(3M%jnUZiCt)KAu<)+i+v4q0i4r|+D;v8(XNb)h?H z_rv#B8m)TyDh9yg47m&}mA~{$|L;!H{s;VWbt>0XYj_wn&t8%rpZ{me-u6jNG!Gd@ z`OE_;E*`Q$`EKQyq8r>Rw?IYDFL}LF9NO$)119gsAc@IUgVCm;8D(W6o|doJY5R2w)diiZ=}`7P)r{oZry87J0?caD*&;Em;Mv`h+iVJ{zC z!#-CT37{jm4{lBooIJi!Wl8Y}DzW=ZD6#m96r?g3dE`ck#|>#X=xW8FNaqt+B$-$D z+dY$(siV5yu}-PiPlpJ@E3efGC;ZW~{j!wMH9SDWDP_kV3W7R^-sxeB7_&UtQxX*R zF<4yE@mmMrt=Qrl%MDzQk;O+v7H|*3>ZXpXdE!;PMinOJaB*nfW5wHB8-Lra+68|( zt-cTWi!7LwIYH35Wwg`bHOBng0GpcAZfEQZ(K#8y^j9gvAua=%N=0Td>~oBMLDqWI zET!+?*FI6b2em2?KVkv7A|#nM13!BDFhkD~pT$Rkmq(^OB?M)ZV9bhudp@4|!*FZu z_2oj^*B_;@{wOt6whm;mt8H-C9&;v*C!T z72HP8bQ)W5b!y{sCM&I~tf%oEjOH+~_r@J^^B8ay?e zU0^a%EOi#7yo`6fDKQ+H2%2lsstTm>=YVP4^;sBFccdAJ$)0z$O?x1Gmf&*y`AA8o z*7nFsWp!sqn@-NoiTN`K_J2RCxKy zm7OA+M=c$CMZFdh3Z%-&l3e-V-{gFz>9j2%qxPlmC+ggjXMPs^E&tQ?XVV%U9VbRg zoD9OdUJxF*cQ!Fh8GSY?|CXRFw|hA4`F((Y$|vo4zxCOLGVx7~n|q6IhfE&ccQW7R zD9E5^zjdo@WY;Wu=<}DeV(%`qm-Tc+FD2=_-}v>8TmCJ1gk~evA8l#AmDxrSSHUap z6$OHIGhI9I)Z#V)IZo4LIYo|~>k`Nb^#&W($#>UQ-T20W)882OkaTo09h{8;1y z-&n(zmvEQT%UI22ajh55;-aEK-}3)#@+n{`KaJ|BevmFSsUt(9EN*qZr*&W86)!Nk zo*_}6&RleMx0tAf5{+z{Lg3!fqKjd#JweqnLKS-_OD??$4BTh*q2d+!`RC?p(eYX> zQ*wx#xt$DdV2iByJeORkpU0jl47fNP5}PceSYRT6i;A8wsBc0{Q2Trr6H3Pt@h?37 zz4+w!GOw8gT^M%~QtKA}%STE~c4V&VF?jS)-m3^NQmi!xfs~8agSH{6lBm$M8j(DKUB5 zu~_ip#gzUGrdyY2JUU+P4HARt;xHkH!ln_0&w@98eU#8~5R{$OF6^A+IekgvW{t_S z1);`TalMo+uNU}*t)9ehGdzrE-op9LrsSiz8kJ|IN=4utyOVz6K=GXw}&p(v!W> zVlp|X!gJBrZ;jMDvPq8iq)k2V@io_YOU?*(OaI9I1)<$7eaa>Ab8A&+u}u7M)+V6FrF^Hq#-?3%{AdzedtEA)fMaj*vSHup z?@P{x9NE_?Fwuu>8O)YJ=y9vaA{3LBY@c}RX5p5+E49dA=u4BytL~TH=e#$>xXR-r#$EUNE#A$vm-}HsX^$Y78biSUv8O9Au#Xnf!_`#7sZWH<(+V_v#keVK? zx+E#D)GK0)#7Li_s%?`++sxZMrMr{C7-d|~pv^6#N}6{D;)hL>TZ{Df?Bn%oWYJzSbAYz^Amn;)|qMJj~^fUcF3dk9zx!&(rR2bGx^|dVYi&QA z#(Aw@-5%#QY{-B7N$Hrh9VsdAyVs!tc_zbHR!4=1LV)LOK1*{OS&hjTHr*?gm)@K5 ziMMK5^7{S2d*EaP-oaP-%CAe2d&KJ8|KiHt@nuSfZ`vZ(kz3OJzQ#Qb^7bCGD5oY@ ziu>S$L;iAw*X@2>8nAu6Q1YnsTAE6^&7Mlwaln1Li#HQ7(L5Ke+a;l}tikjAzk*s- z$%3mVcY2d;yK;nU5?9s@hE|8tj7g1UCIuEs`^0vGYnXHw__)ssw_H7UiJZ|K?+YXe zcwZP9U3~DfPyJ}P#Q#ePL8>uQqC8ALZ_Kej%*yq;|tBe-=u={F}QA zk7*rQkL6jbCJ{(#wC=A`#b*TgRmP43S^PbIpJ9}z$^Dkqz`K7qLj4h5;EB&-)mf)V z4vDS4&MrWmQ%%RAKJ6&$-_|iar*nT43~}hQY0(%<0t@vn=WJ9aTz?q;j6PM9Ku zcsNRfgpoBb(Pg3AdYj>&U`t|*QX2y9(?-d0fqWncQn9ca zSDOkfbv^N94MRWCok7`C1|t=h`u;}dvLD`Pax*5(2|WHf_w}l-{L!ltt3`cNVT9C# zFA{Z$YkPdxAjeY_huC)J@b`Th)GB)++Hd|RFM~JS#j^C;jggY={(p0O8UsXnMB0x* zq4z`1BYa5h34!@ub%2V7Y9wTiSX0!w;N%s!e4lR@qW}4uz*3>Bx^4$rCdNaE(9EBs z5{X)I?47L#W|QBVDcKK#&*IlL_Nsi0)bbsSP{(q1_b6dph^D zCOsX;tTbwtoeh^<43}&qKHnl~*)9LxjgLf8eDaA%8|aX~_floDJ4hH+nZ3{)jqGSO zYYje3eln^Ts*l#vt8HYusP`1O=zmrMQk#hyYT4e!qo+fhCgkod&CVp2w)OahA#Mg+( zr4VocNXq|VTu6ooLQwg5CBe%fD;%hI?jQ_f^ZDu6`Ym6tN4~64`J#VkeAwl=(5l(% z)W5DiB8ES=(;J)eXa*;!?vVMk2SsNYM^3Ak!Ym-gZO|Pr2 zC4XkVt3sw)Ow_4g&Bp8Z4GMcz$4i@rJA_*4^Rf2ufGay~>q=39-`E|M9>|`e=;DR~ z3;WYu;HgM7g#-#^?9aYMXRDc{PwIWONl#aijKM#%JlMry-K8?Oe#=jT7r2`*?=A0j z;&Y$PIlP@TCl}uv)mr`;+EB;IB9&Bl2H(gvxSIQOq#CYhOOI;6(XXKOK7Er^WrU1M zoS7FnW}uy$ntk#;?y|?FS^!pldBs2Rc0W3PUieGyQ8kEQfrZDPAB7K@eB->Nxo$d7 z`?K(z^x5F#?hQTkQB5K&QDCzRMou zkCweg67hj|?kWBNZyR%|o&LviK-N=anX$39&4zWfRVS*=yxA@yij0hmr$M3~(F?bsi68>fVctf z8I0WgL-VL>TqAg%5}6AIn~XY6?S$NC+0Kq|FEE^}H8gLb1Gfm@yb7?4A}XX_*c4(X zd;a@|Uc}mhLusz!a>>_@+l1PYUz!Auljo}WaSDD#S5Es{dj z@h`w$+rtprHUnPtP5)?@KR_`1w2Dx7q2v!uFpqz~;}`c4*E{$Pu9cUFRkBH|+pk+4~M!vqF+dMPh&cS;!JQg!8_3| z`vUUGyu`6vre)WESe|tvg4VUOblOXkn;n^z?iyR)-Lc;KLBGSvRZ|RXf75Qc2xbxDF%?IG`0Laqh^W?^c9U3=~ zjBPkm_dp%rQFw)w8qh5>(O5S@rzpEHfs(>|$c^`!Nf+ACnamf!E)*0LFy@WI?QHoX z9x9Ns#Yv;tGKOr5>*~7TTJ8RRGOjDlmJW%8i_U=)Zfjat=YgRi;|i@voB$G86Rt^i zWk<5+K{T5^o8)=qV&SN2Ae)lLA|aYbwA&%b@7E^Y zPo_vFic>S3;qiiQ5nB6jmun}!qnOs&L*{k|@9}w`b6(Ha z^Z9r_9`}7e?ng_ql1IwGjy0vm+nRvt8;6F{os-m#VfVKTp)XZc6@ESNd+D{QzM1_I z2e`l~stV06(4#hin-0Yf>uem+qT<`CH^?VwD{Q@L%YhT`(q1 z*QN;=GQvm0XTR40P%aAo_$#HW8N9P?k|;uE27YGU7C*SPiY=@YDRsy?h7i=}rT+C} z{)x>6le2aaLd2yacsA? z%uTcs?{6d_9wat+!FFXJEQ1$CqlgkP{m;gkwKD_ZWs)$a(rf?rxMmOc^>nIomu(ia zAXV|VOY3m$q#4Q3Dmj0F)5pUf)%B-!1C49@_g*1-<(`pQA!30`1RCJ2*&(iJB%$XU zJ#=UqP>$Eq()xm4qt+3(^8~~4sjhAdWJeHi%>O#6t;!5H2>h4O;7hOzv2PJ~cXM#4 zoS;(`>g{&El|OsyAQt!0xelAAC!^Y)%7fM@r_Cd5M5({1HscuwbXB!32`9LG>=iLA z;mBxV6bmSI3}0!D!X0I6t0oaV_5blau+t0X1 zkU(L*Z%~5J&_cjOh_rR*f2%_vFHJ2Y&8n~K&*06^%j;;)G?8{+aGeeWYy%3_15Gtjz>iMP;=+uF|Nl%YnXwSMprQ5=s#A&RH0m~xchqDjoFn_KM&QbMX zk)@Q~jp{-YHE$v=fj>yfBgoH6|Z}e!{Gey|=nQ!YUzzD@8p=uCdBqc;cDmWrKI)KbtRaFIDJJHG#R@DEgF~qsS%|vG`{EeyeXOK+p|D% zpW&aYmz&?Y6ums%|9UDx^cF3^2-^-c8hjM^$#@)`mG0s{8X?l}!$x`UGU-)eaBABc zA^;8z4VC=1&EN3NeR#xuqEX|(!wU@ZdO`e zt_0XrDowAwQGI~Fznt?#wTo)wT$@YTebEj{54D~m+U=dlNbf!6!d|eGyFKNzn_p*i zyjKx=C|$Q1Zo+U1H{?$=`ZyF8v9dU19vz4anvIkBYOjrMAmV~WKro?3S-ZK_IZ4Oy zcul*;BZh`_A|Ks<&&^;< zMW1DSwDSx!^B*AT$+x9%IknCFbY^yNL5es%!16x&ig070y%u{0x2&zbJ$eBehLJIs zl+|8L{N&h_y?^MFNh)*3XT@`r2=xaH)RaDy&(1PhRd4F+4GrIFYyX)Lyvcs=(B832g`tthTH<`RGNoi7O7J^$8 z+L$2EBShKL!>uv2fv@IbCDZT2S1iOoD86+%r&}W2!EDF{Ipu6?mh1JZ4$0tiD~3MB zB;4$CK6%h;gN&!gNY{y7R8l47zG;rZ`_I+t+!N;VI%-CV(2G`-X6SumTrZ>eOA;w6 zr;D+>(_=$b+NF?VKn9PSH1~CvNN8=9C0_K*{#@A$Ppb?G{VZH%ptLGwIRkkF{IurA zLrQSNA$KdDj>zCW;&nfR7j3ic)8cYgs;XGF-amf=p(@si*=Qr5U6ROtZ)lDV+SE0O&%wE+r>h^9Nz%04Jo$=N`Nu%Wg@B#S5LfEvqyodN}8%~Am;JvXudtme@CYM?4VoyW*B>b+WUL4o z(l{1e3P{a%KC9{;>ytdSEv>MSf~F8;0noZ4yuWW#3ZI5yR#(@3Z|_auNubVLx0Q1g zTeC~Tjeq*sf$<~xl8Qr;9+BnoDSIA9l_?(tEMqJ|W#zTm<*cCEaH;mIuZ z6hgp8uBV^R-TsA<#@GGI#Mvbe>J*oDI58&t2zNQ~aMS^|LZ9(dNoS%ON$*njQ zlD4_{#Xr$b=(vLr1JZPac1S9)`_vK}rhgO;6tq43b@*~rT5fJUfg}kFB()UD@U|%6 z`TIrBa1Jst?&ecIr-*%{T%`y+4*>tSh5G?t{YQ=)4~ndIQTWh$tGv7Dkmt}d27#toN z8bbp+l;VFO<$wJ8M&{msmmleWLNMJp(70ndTD7cv8{OQcUWH(F zx1QJzYUo^tfaWd`aE2hEp6?w|TWe~_XwAOVKj;ZvLk$ETa{rtytrgj6rnCUaGAwbQ;tiVDt6D3nb zaTZV1-sPVTcTF$3H62AhR&y~ih1fh*SO>PhI$tL5EZ%XKB2J#m>|S9GL#siT-C1;& z*9FF@%myioNvtl|eh-|L-HSoBY`zpc@X82yjSwmzEddQCBl#!Y8d_#=kN)RNzbd9wcu zUoq#SLOWYbao91c7hejn?q*o>vG18anJ7)vu8H=LD>5mp3LQZ1fCvxU9au%%;j~39 zF_T!hFe0YAUK^BBs%MlrP1Vn39@mTKI(AWKYY35W4N_;in*$U33#1}5Ii;rl*eoN~ zP{bNilGrQuC~-#)v8NCiBXK1qbA4kXu7)4$s*?T`p$mS{95<;3^@cKO>>!0fsd z3&ane(LSS@D%WQ5*Iay+)L6kC=_wAa!dsI$YO2WbpI?5y^htki{U~Zle@fTz|3DU? zI=e_d7|0n0kl!HMO;#oaYF)azU?tV5e3&GcV<0;s3exI{%sOhe#u7#&D^D!>xXSI@ zJeoW5xb7()v}(5W1n%tpo{R6I*7YlmqN)t_NvO&%czaDG2YQ=U-cacvo#~Oxim@k4 zjYlexf4sLRpu?Fw0yO`0m@>L|sIBtD5(g;op_iBL8quXu=A<%eA$d?c2x~Pcy4ofA z?!4NC!&68`?hWWMCaBTYv*U`i4|z4!F$LhW8axv6V6DIaEips8#pV>ejp z@cDo)NSH>@$WPu+<}ckxc?50qcy0wX9h9Z`m~%!u*A}f|i>e6Ut96w}GR-TbuRl*Y z8l_$P!uXiqI>jwNY*Eu)-yD5waHq?_hat(SJMI2NMiRO7&fV_Pn`(_l&UFCy>Re(+ zBsqBrc(b6pW@8lM<%dKr#K}jD^KF2&hOU=%@%7vXD~;8YPlBAVP-Yx z&UgZe$nzEgls(&XexsJ+i9ath7v^=20f8mBJA<(Q*l2kt-YNlOg7P5AQKTqrJVI}!Qt`0eCp83}n2#-Ipnr8P!9>o*_;!BIEL-uvEIUBFGPVTHzD_@*Qqljo*$S%AMdA7!VCiyGd z>b2%YZpj5X=7;}l__AIL$E<{d_>ovTQA%3nm*`%m-ayUbF67sz4!;RmV}2O8gE;+d zvS#iQ;^?VBJf^HyD?7 zbez~lOaI9f@4HlByKY19#4{XPvAgyR&E8tr7>ufy}zP zf89}rD|u>e)~_vY*(ech^f{BcK1(ku*-2FES<2Bk(^3!&hY3*y7``6KaI5)v8nM}; zm*Vax>WB0J;qODA%5I7OIwT7=5_Q~+L@$;cyB|b{)J13Ei;^6C{bF%Ho4x*;7ZRkg za#uIk%9NN$qOu?HCZaC!ImSEVu0LOQmOW<^zO;fXhP9w4(VtevZ9)ONO}7c#?i5_u z9qOzGxqzx_UgHYc6j2F3RFvl$h?R+6{+!#mu1;IdyI%@d9<&uxNcDV9)~XW%mG7L> z6+Ur9J#)~7Me~!}i4Nt%#w8p;kkUuC>dcfur9+v?;SG5--E5aE+O zCnUsPvK9@t<8Dsi(p4Q4 zTTLhww2+JB4ZQ1gcUih?^_Nh(+{f8#Zz4;I9uoN_whAPpn{`u{QC`ZW5^%pgiIcLw zO)JN&N_DJH`TU<202|}yP>SdC*8a2j+DhYgcO+TCGMVpl_ya zuk7s~(0RYT=takgU?>le?r7BtyH<5c2A?l_=q_OnvCayV4jn%xjVy`c>3PXgru2!A zuJK@mB(*u3>cHldLe6EjYI>3vY790%z)oJ12Ke=je02q}S@T)X<+P5Pt|3B^Mv1D9r|D~J5gXnAuV{NwOe?1Nev{g!x_t3UY5{4isbN5;({ zRfUlZR6SrQOnye_O%8Xt<(?uWMh^@lr*EGjBI35Ci1_pwokgoKDw!p^&^-o>RoxFL4*{gf;~)uf_MTL2C7b z$h8W;cDTGHYEfCur7g2JJy%_0X4pkZt;`XzW!UZ}q;SA-)dnBjd!HnccoWN$Sq<7> zNM{$`|5QOutHqkE(@2XuC3jH;H459TlYc|KF z3-`{1LQSIkBYw1JvG6uXT$Xvp|?x3a*wAP>445D}3nSVd>>nc4Cip#k? zB6VAS=Q}5GV9gkZU8Y!GnH?DjYr5_^@X7WUvRH)=&0OR>p3pdkZu!!QL`e|H$O)u$ zP#F>ld;0moLJ?P_+Bc_hOF#7|BGKa&ddc_L{J-?3?R>uG_`0EI)KpJ@nW6~mpSl9I zL|Tdsfh4y*VwPQJu?Sgbk=o;WMk|ihm2c1Cz3t^7-rM$-AJ`s@4kSEY|1Nv89ii z$<#92AakRN*o^5VDQeL}Z{D-=vmUoWab1w&EUG1>qzN!aANmH8zI5KBQqRwym;!S>x^w#8%$R@V_6DB&dhWndAGKj>2FGs|{M4zB~DKDwP4Z1POk%K|qI47NxUf zyf!F_6w)dO8URJu!{fye%6U)3%d`_`Ok(-7RBk2I7bb6`r9<*~Jnl%UCuK6f-?|2` zD`P3s#evfi?y)kfgD&irIFxd69L^%HR!I}ZmI~N9=T(S}_EA7dwJYv+ zO4E^=HCROOrD$H2diHPurQJ6mT5L`2R_W+*2NpzdS5XSShjVxGvhHI|phaZ`$; za-ko$6`yD1Go%N*>wUaUFBT_U@Fs$nvnEm?TG^`FWp(XDAZa?IX{9t*J)P+Kt|;-1U{dkGLx_p$YY^? z-O7U#b!xVB`kgc}x`KC?x1*cB;paXWsxEOzCrbQ?A1Tt-wt7fs#Cyv?m~qDym4Jr` z!~SbfmZcpvt2;#07QEWlVmj&xyJx)KCkYU8I)|RGj4}tPsEz$ZS+X3lmt@)HSl%2C z*ubw_+ylURWbR`l2_8Sz?1T}}5}8muF@SITM5VB#W#g1hksvzw;-`f&#UvmQtW>>q z&79PKa+E%w5Qf8L46{Rz%N+6+vUd{OK3!=Hl{+G8Eh*!J~li;n}(Ffn6{eHexzOF7ml8v9tl$QJu)Q3MMbl zIDjv~VM@l{$+;y3G3@t`A3rW3CkNO|C74@Pb>)Eg1lq%w9n?W*+DWarrdnZ;-hmFi z#D|B=fstutw8*jr3Dc1*rZ~{JlYMa&K!X2Pj z?bVOqhm)$iL?>uzYd??c*PZ`akOF)c04Hpf{{H_t^o%u)mMQ4nCwP?G)5C-X4mie2 z7J!=4oFE{hUFA1~}h{7m(|7K$UTI%_h+P-9UlHfQa zJ_T5Tky(0)5f9pp{DM)JI7uUmF7pc6Xls}se*b-MZ~xco+gE$ z8IO3aYM*XyYeU=oVx(3RLAU~=Q(+1}I<7m=H-UCW(0#DkxD-Wi-}G&Tyh@tZ@#+j8 zhr(KPy4!1Gum{1TH6*ILqB&DbN9R`5?W@ln*gesVj4g_`1hvH2dpC%)w%V+*RD68@ zI7iOCp>mVwA?$Uh+3qPaV7+;22w5^tAEL;6o(t;S-_v+6LcH8E`b649#^*B&yIGoA zI!=QdCr(2ES0{m|!+1h?@$b{cPyFsPic?clZPkw)9UR0|e?g$Y=3DvHWudlwBsrOn zprbwta50_%;7C$bRRuW+vjxkx_nnR8T~NG^I&U_-*->Ysk}n2ru# zUKkl6aw=>k@JZY@C$4WtEe}$$IN10Jj%)Y2c5686pn(s)!X+Jq4?dV6m>(7gY|16^ z!8Zy^T~e|r9$8c@xq2SXMJ`30FuDfcf<`&)b0&tx8M#H1Vu%W02Sd2P!A2Cs>;HHM z5(T6=Hk#{XgF0bw046I+Zmx6dGI^W-{ymK2@qz$xkMt~{8kDt14b`~cii7m33i@Iz z+%?e23%SkPd`d`?_(*&rbBC7CMe(WM&eb?3QrHa2>M z_lSlxt&23PGope8P*W_w2H(3*o zJt+eQK8V6Tg6MR{FaU)eK7zowZ-{gu6oI3FSwR)7I`MYVLYR~dN{7(Q;9pmG6Jixu zbutq=E;j>Qf*z1M0w7U7+yf=2lro`DLlq`O5>nVyEE_%kTFzud>TG+v-wY}rlM{l; zUk(bcRhJ}A!z!Ex%Q}u}m!jILnhY+gZ3b`Igf#ZKJ&oVcXFnyQ)+#kz^_pKddP?Gi z&;*Gw4g-_L(?8^v933ZiFGgiM2wS(16t!u*yEeg95v`LFer3Sy;Yd_&?Sp@N4GV5` zHHdSICzJeGjBJ%O^@x{2X2QS_T~|jZ1MGutOhJnKAKFPoCBtsXsegl6Woqw-8#wuF z>JG6Y4MV0PxE93?D67B78gvxZu+Q)`*l%Ch(%ru1t$^jw6KWC_-d=8Ml+0{+d@!;w*Q2YbuWoZB+@S%JwvknkWIZk!{f5`upR9w|Rkc}Qi3qDsVdH;qk;(9@k=kd>3Vz`tt~Zn_FWLIn;LQ)93jaC_Tp*HNi6dl$Ri zM@QiP_5W-&iL;7MCsoyQ>$!ln{Rs)5CL%CH29F}b20JOSQ~wrCMwFvl@-hmay3e+? z6{hdl_d#_>wv&iX*QJOa`Gvo4t|-U^RevtOnp2gd=5^r6@uu9iFTdyvXMIEtQsQ=9 z_ov2h?B4O}mR$);f_ol43awKf`g7XP)Gkk}X!{gr@Or=I(K#}BeAgz3KDKg76J{le zi#j0ZMCESFMiV_<>-W3eHN5%x(Ptq{SX7vBj>6*L zDfVxE;b@*1+h%DhI_-&}3hY(Rh6l42)Kr)fS-&En!59)YrDJ!Z!Pht3%(7@<@kkF7 zzmp#3)@hK{D1YRy{LCa-x@Ao=Ow`Q9)VqsUpn)4QH8x+h=)-95dmL-BsQvwN_;bx4 zAF@TfUw;r4^=5DiuFMvRN|qd~WvO6|xlt$b!nWz@1^OocnfsM-izKr`)lv0yFXmP#MbUX;S(aR7z708O^6o;zHqkpAbW9y434|Vu z@c%-KG5nF*DvOeg&pQ@s6O#lMaFOj?@}_)+SlL^{3@M06E&cvP%gb!o!z8oi+=1Wa zr9%M?v&3bAw&@e|ZtkM9OQR+D;~516*0To;g0b5eoUyLEqa&K+6(ZVE5cnl+W_O;xubolf_u>TXCFhI8bv zUytE;pw9xI6pU}E-L30diiki=#VCESjxgWkQW&qaToatwyPLb7*d&C59U&JZtR2Nm zW;Vl2B+vOBaver0^j!v$V)*yk7g zyB_)}=rlFOeQewqds5q{=d{{8bneZissA{1jj6&mG7b|vAWVRd&ugC7OI{JCB5Z$) zOMZvW=V(1_BiZg9#Ya?vI>)ZYKg~dP>)l^$P z?~40yD_EFzUnKm`v}oE4{m0Z(;8Bo$lP50FMgLi`lcj8QDw~hYo;TzM4Ok&KP4i?A zie7QxGq=sZSaf|lzl~9XgZrmkxYda3#{m7$%@X=0Cwf&JE2j_dYO#;rGq7JgY=5Es zUV8uUELTUOjg)+x<4tzsno}o})ed?cASRh$tPWm+OG ziZr+c94kb^1jPdUBbMEg;B0}$b&OxMp8QSNQ^sB~wf7k)z(K$y8s{im2L}(jGsdH3 zHTqN;BAdZTvU(A4*XXh2rMMWdddOK$%U7dzwi4H)n*j@p^Q%r7pDO zz-NdI0T`U2M%))~V^mswKapO*>*3Tkj0LgMc2qr}&BQ<&5HC(R!M-K`_Vn>~_eB}l zRrAEE`Bum-{58a2jZ@pC9ewcI*)}6Nz?0b7Jv0r&?3R&P)F^}t3@)b(UI#}bURTLz;Q&)7K)ea4Ek$il)GItq+XfshMsosjEIy4+FSh_`k7!H)dYly$#rN9>osgpk!tl$1iR)d_T z^UoiqG68r z1Som8r4H5EkjNow&95|VOdpD6f2b5>4%R8g8q7)IIWT7mBm9sJV{0P!)(qCy+!aiQ zITDP=cwz-=d;6~^@5-^T#e^hi+qU{W{P%8`Hv<$Z6BD+m81gW#uH9{x53Z5$rGVlG zi7Sz9CmLcn5Mk$?YuSEi$*TgNH`jmJy{mAfIHrAMqBlf0WuaJ~1?owp%rk`LERI_7 zNJ*nT5f!^ax-~Xl)m-DJ(3+d~l~Ho3kNp*-*N4l&is|ngwMuDBwLUp--RhmSe#RoC*2t;VmLTrn3L8W z6=G)X+o2*>)nSAAPQ^VueAJC_U^E*g*}jS4c}*K26ngN%mF9#H-Bvg* zTBg!Eq9OF1NtKFrus#c7#Xtc}{V*V?)K%8q^q_F;_nYlg6*ZE)iVZ*yiZ{;hrms`G z{a&d)a2pW^UGHis8isq3^y-i1znQs@9IJHZ;qNCEMVTAQG%Krl`fhAfS#e$UX`peSnfo6aHAt`8M~!w6cWH{^x_*qt!+V3i3ffH68_?}iAJI)#|H&MeKCE)if&yg=F~QRbZu{sOsLv)8Tf-dIE~+N{`G;rwYBCbp*VGqyiq+f6b884CW6dOIEv{QaLH) zXwCP?#4JllAn3Hr#AA_Avh?rIe<=Z9f14D?)H|I-G}~qwF2=~4yq?4RnAyr=i*H8@wKO+LaGs5Ly0flo zgEMlVP?ZR4F)!z)7a7_UH-fZ(Fo$HA$qbG2&AxrKt?P^xa#Ombg1^9vOK{DZqm;~T zDw%B^iQ4pq-|Vw}da5Sz9bMY-LHE=s0vr;DXlyIHo$7e%@D;Gz?BcIFxMfy&%k1_C zn&*CnuJJQYWgTzv-H|I!F;|yyz1|&4k!d2H$ud>sycFXZz!*{V=X6PcpU#{q0~a05 z@ad;r1=IqheaLT%^<+70gL)bK-f8elvQHhXs}#h#Mf76-Y^{qw+k8LZ)Mq4m+oi5a zdwW?5D%$i}zFe7zm=fKNThO8frv?^3fCsRlAsEDHiz&IK(D=aQ=xQp-;ZIKBYfYQH z9~UHs`3tS&hN%*R@;(8Qv#qR8XSdh-*H-3Jj2pUd9_+YzP%pyhO}>a8Gvd|PW62jV zJOu8qai-q}CSg4*qJ*I<^>dw9**wzO#AA&bUlUd+ZD-=tLLvMq_|1R*hTrSK{?MfL z?Ttng44KNx?!n)pV4a#a^4Rn3SCz6vnJl-Px|?O~{b*?(M8tu+DIN+uJ<$$%D%0C@F1t zK>`;g_i*=k@AsU4tdGp+(4_$OmTMBEbe@g7{NwQ6Bd1BX-;4lypy|5T!aGV`sXXus zi^shyzeoDy@wDGW$R;M|?=OvOmSxFN!-{_pd^amb3*T=NW2D*F`ZUi`tTVjZXIKPa zRvORUc&b92(5U&&q0v9|l3&ThJ-Y#iI1_#lECeR#&xM-;yID|aCnoP)O#Ud6wz1wr zf5~`jGbN*K5Q!LZ!`=@R`mg2#FVrY1OnRn|-febmDgQ=cZMf`#5gj%AY97}|i0D4+ z-EH=Tp%oS+`?_A9IB2KjdR;XnbAS0Hh`zi%I7 znd)OVm1jA;-bmtaX8#B;BDM!oo5%XR)BlN|UPt>Ds0BB)ZgVDEk;f8jXW6HWrCBQ& zV|->_?|Z>7!B+lLGEy%*thIn@+`w&h=@P?5qRxHnSaFP@A43xtFx+*bVz=%nF~*0G z(c(t@@gvM`X(DrZYGdXd1L^DC&0*)N^$Yu+^KUE&2%M$w9FD&H-&&t8pJA^3;blpm zB!5%Wl;nkUpY`DmB;CN>M-@`3w3%#iDy1Vf{++?|nI&6mJ2q$~VVdvpkTL1YZZDP| z*t|9`&IMqq>UzlJpE$%R93gF*$wmG6qr`)AkAEic09)

    7U&6D?qQIYF3+(* zws6b+PrDG~YK&0Vo{pWscEstCi0BQUp8ca|i zYVhi?5XUWDBk7z0_6fFiNk-OzG^OA7YLnGAP)UBJQmhpbjE2Vj5t?B;$&%C5!$`A+ zyc7!uGgKxKMJDx{dt1_(f`b=Cv7ln_ub58DKU@20f_+7mb=2&H_r=1XD?QG~iAxe! z0>dSXj+U?jOT!$daORLYkzOMf+otIB_Q)(7O+^YANZ@NM52o3un7;-!6*zqBW z7;Ohl{=z`5O|)yc7I3k)@gAgXa;Xn2Obge`l-?|Krnu9l#OUX-0v*WY1({E2s}d&sN{2f0=>4zipD#WYR)fOSE@ZeNP-F(h0YMkho5W!ig3R80v}N`uV{+ z0?9Q^G*UVG#54dY!j=keU)``Uhc|aYBss}V&4w=_YVtu93-6u+m*8sSidfDjb2S;a zLe0Kv0g~9k0cBLP5q<{B=LK=iy1Pm1#Shz(`8sOCsLHJ-@qJe}F=h>hBZ?~CHhmVQ z98XXXlQdn-mTS0KlzvWsnVu^~-;QfLyzC}?Bh;5R;GO>_EfR|70~QxD6Tjz}>V=Cj zzvOKCJi(Bhai%(Z)WX+L`AG)3JAFZ<*E~xv?D(RzBAsi3L4Kv_aF-@qd*fwFF>{U6 zn8`*Qs>G1EE*>ulREUj(f$ zRk&1>bBC>MciD(}%|IU-86f!7MHpeejK{D97vZIpq#4)mN5@py5S62&&OEsH&=gnV zlaRG2?lzP?L&3~TF@T5XkVE^Ybr@b^-hv}>MBNXeH!BN;6e9mww2wOgW$CSdbc5Q$PD;XK{10^Rc~dV@h!rEg9#RV=AA`rAP1hR#m;>l)zhrvI$u>aG>D` zznOndpJpUFUHwNJ^iK_#o*%)zVflkQOXw|wn1`W3_?2NkTn#R!&l*YK;iKsDTC{^p zZ?kPxEF;s}xT9849(oj!wCn>`m%i7p{8m*Kx*!rOM?q#_(*2NEH;rfGxcsTio{U{T zP;vVkcC{P|7W>a5UCI;b`7bQRa?JFk2#Nv^NoR_R)#R6q@QqHnGHqCQSa4pma%`V* zSP%PVgCFFO+5{qx#`!jGIA|B#S{lSyyW{lSMdF>|% z1sGSy?n_g`=E!-+1GyvHN)(iJ5}ig&s|9@e=6apVC8BJn?M^2SrsQqMzgNL1hm?EKnIww^87>ri1t% zv`k-5-ce}3XsT}Mt9JP^@560-S^l>xR+R|^>y!3qknS1oklLkL%zlSF(93Ar-WdAh zmcACEyE{QTwp<({Y9!j~`q z-QQ|X9wV};qF%RtQy~*36O>Vlh3)jjvi-A>N2KDLEyGc#73Yx-H|wNnPgq^z zCJZS{^Zr<7E>)mL=&x*M1>%n@3CJ7LxLdhsiI2s&3@(^NZj;{*TuZ_aqX3X>Y0>WN znf~9dJ8+fNDLC%8=Fb}*5^)BJzpaJ5qWr4Egq8XLQOpkqYD&>xW|*JN(Hwibjz~h2 z$9Ri)5AMbSe2#r!7e!wl`3~})NaTS3C7qtY3`Re)CMLaM+B901z~SMifyl;Kz;5TL z(Xdv4Bmro+J4@w z7PT#&8=8=Gu-*P#mfbo_N4=c?gBY`F`{`q=Y2VG&@8G^g^%tOW);;)ZbX>$1Lw{a6 zV11|;P3&75o69dLcH}`g?7aCOWbwsiwo0$8Hs76=r#u!g5RL}Sd7t7 z^`nL6E;O{EQ|jxGgF^iui=W=ao$>H510q}j#n{02OQ*5fDfi&94)c$vEGuz>;;JL6 zida!9G#iwGSj&f(D23LaVnb>tCNamtcx-wRlUvs z0d5C%i=C*#WI4F@e-B9!V9Z*Xpdohfm{+fGr*UnW5ObUuZeq3OSaGHP+AEjJfZ{q? z$&#aXBa^F5s3PT=pHs8pJsR~Wc5|TqOD?@l``h-T*oJCCgBMMC8o~0o@A18BR#qxb zWlHZ!_`hH$@Ig?t_RIdX5RPI;nrjrJ0q3-d^sv0$;SJ!*P*+FCN=rm%Xiqn#IGfX4 zk*&vVSb=uZ`yXu^@uRWznP~39`0O<+b1W9MFVtoD%(yE1b1})^GYw0WA-o)s zN|lWd3P)M6HTBup=c{TyBdWrOo*W^@61@vEfp*2fMQx=nI!Q-ci#?Itb2#Gij!J6} z{gX0QqZUef;Tk_aeE0IMFm;Y&Iz4v<`xj%pMU(*X^K8VN4xtxGY>&0)PG9HU1?Cui z`8dgMOugvNO*!+9+#Ub>{#bzz8V)mUZ=IS*S0`Wx9#a2RNIKfjAj1{!QAnxpPdp^G zkJTz-wH-{=rP*F7)#h6B`KC+9qFg_KuME19xNkFN(;^gzC`Gr-zSrPI5(^cF?Cv*w zl>fVqj~TGM-2C8!So*QBbH5O4^3pkNWR>%5rTXeX2@j)B{*rsJ%@^UBM%GOH+lHgo znL$^XR;I*SUwU+p3x1^h^lzsyF%xW&xMf@UgfxbtNuY@zQzJmx1RTEnm!i9XSv=^) zw!-nXlHgjuiWr`l*g$%;JkEHmv+%8kNcO#VrDwWHC@waz2dqlV`j{z7ruI||9D2bI zY+=Isek^mfYbo!G`si4ZGoJp1=I3(QLt+J@P0tShHZKMI4uxl~HUILG%e)FgM|R*!7nwJz z4tb61C8BvL@3*=Lb4FYa<&yNAZyu*cZt(r0AJb)H&)1=rc(yhd_x!5~QnEWX%$4Kw zd#a`hNg42W%oZR<>3|-eciVdxcsP({aBMdDmsmWI4go8g0o}U343^$)e|?w2)Z=MS zwY4PHrnm!kd>;%m!vuW@tTMyw`RCoz!?mdFBYcq_t)VuWt4SLx_!%DkmS4#Jl*|%Z zbJA?JDles)Oh&lKdH;>G-}~Dj!f#BVfumyx$_71w6(`M>-2b1_oy~9EA|?-h6bLk4 zPW8GT0jD$%IB*x7V(`1Xf<9X*Qp%OBF+SGPCSjiePzov9;-+%|HZcfnLgXVk#IovI zQ`|zVrNa8LdoI2E5PV=Cfl*9Lb~ZrAc)S|k->9;N1vPa7whsH&|96pa4JIDbz3SV> zUKWYqkGZ1Zsv*cKj94b{r?vVqAQzO5){b@a6B`D=^Hl36_Kj7mF_hhv*N#fO$>9q1HJ~CTuV;--`fAJD@{H> zSCs`9A7|4w>F@;0bR8Q&IUS+M;qZ+U)*mHm9%n|J3KZ03LTH-wKXXv4ICyidNU++C zvXe)SOv8|t0DoWeK+S055f~yzDakei0oG+!kW@0LsE#P!Qrv5+3Hb=-ydbk{J-tY|@bL&%4VJKTW!Y>vOt@U+lY? zFGmY`z3!vXI%QHr66oWvI)nOhLgk}A|AE@w;G0sCFhc#v%xfpM*ONBc*K?E*f$!o$ zad5G5AzOT1-!H)C`?#AWS+wCM=Dw@Nwz`9&xxep&2)WE_>HG57%T_St1;?>UeGUgg zd?S!OiV@xg8;TU}3o&-_(h)3;iUH}@A1%zPIc|1Osrh={O9#H}pBX%@c%dP7{bx@s z->!=zi}P~h(pA>%;LAms3Y*T%AIPyl^e0i&?=2rt8^#relI{hXq+xeR3{bA)=5Eat zd@4n;)&%T0>=JZki2{JzJXsS?za-kRr3+CfTAzjGuElZs@SBXyM4MOUm0GR zu$Ve=mGgxc?%qt1cyT4xN=lqjk!g*<#TQ(*2=a)396J?{v0r^fgf?4{0dhS-HTe^IL+Fq1IZV&pMTxn~T4PjE@+Cb?s=XebMqd5B=vcX19=K96!8W zg3t(oqe8)VxGXe4{}Mb}qL*2mhwCDbv|Qfv+(J$I<~=20yHWFZ5xDO1)PMiL#{D$m z%KXM1lQCs>zto)?Y7GxPcxU^Y#ZgZ=nD!T`o}3~kjuRvbs8WFo?hsBvQR`?QF;D=c zuHX>OeugjrX(+a&WGsUlr{Bi}rZd*xv*>CR*%Nf%v`g5J4%}>E+^Agl&tuT>Wu+Mu z$1j3o9JSfm1d4;q-c{v42RYmV;!+X2T~Oa97~ln(vvG%Ks+lN!Vanh-I$S*eS&j8=54f|!KkqBY<+Rf}d%yz(>LKhb(dZD}kJBlF&>(nDR zmuUoH6vCHAQYPllKx79Q2Iyc^1MdIoqX{oB_dkCx#@?qpgS*E(3^+nyvQI;PnE)KI zx39VPe~Gyd5_A2Rid#~WQ7`|A$2Uq$5%?~&w;GPQ>8e=eUU zjX$|GzcOwj%4T=s?iW$I7`tO&VBoAuIp|8jLQs_Wb0rG(?`G)t-mckjlbL3(JM%i| z$}-b{@iSSC7_efqxG=w0rfotR@p{rFl9+l)D3byyz3RoBMB2W7Z1_vf$wXi@Uo>Th zQ$pw>r#&4cOP!@Ixu`JN9X-hJ=QDWZP1F;imoIVEH@&+Z;TL=`!$aj9@~_82!x2iqE?vzj5XPxhBTGJT$@~oftLl4G z9M;yYR_C4Bw0!9BqzmD^gQ2wasS71MXLSb^)h=2?BSx@AGp~^rPTyg#+V4kzCTr&2RGt8}GPf zs#NBR{-rQm?$La|y^A)8WJu{M{Dx*{XM3EB*>?6y)Y-PCE`rB~7Z(P~nI)go{X&Y# zHcr>T6UP?Z12cnryT1Qf+>s(3OVMCNd8lS^uf*yy&V|0_Vevf&0UKRsH(`G!Ee*LW zcA9rZ*SF}USGC`bjm*Mhp_j0#>e}5W7B>MRjG3>h;!0D(e!?~y7D0tA!BO$~TZCq? zu-BC^?vQggGIvQ_bM^K&Gi^^4qQ7{u5g(@PrOo-Mr~VDc#XGJL+F> zF&eYhtf;!yBM%Bi`g+Xf)v-RRZ`{uwq?5d{zbl37@8taiPQf)_!op4d6lH8YkNHI z>9Y`5IbCk?1)OBQ^xL8800Ph{QHSQOWKjep$kvEyF~MXb%^a6SC?63YA@$<@A5*g1 zc&YLcwB}Vx97IB|2WZ%5=WvwrUx0cla$VH|T}!Exmx(DjC~?}ETb6TL zQrI-6?*hF`oT-84uI0M_IhmEHDoc-UE52d>&tSn8L&$Q5XeIv?|GS8Pe3P1K(GnUr z^V8m;P#Z%?vCE-_zQ4~Y*#Z7t)rN0X z%bOJ&Uk;KUrYK1Gyoj~!GC$?$uV?xIu5Mn!YgNu=_WU<#elaDVcYiKZpK$G`p61Js zr(2LP-|tC5jkLz{2 zX|X^CwkQ7{MQfTOWu?2ul#=1}cXa=`?*(zS=2+At|HH(Y zpo@=qyf7>lg;_S~j_JFMfdW*7>c8*L7vN5z2qDUm%r4cRH7jyiG)SUBf`>Ip^tkDF zuw-mGQv1g;zlssG`s0LuWB ztfqI|OdCQFlwp6ZZjfIJrinOB*{H;IX(k>r3ckW)IMYT5l9X6KUwO?7_F98UK$j`2 zX3LP*`G#Cf6EQR8&5k&g{AT-$Z6ohNOjcP#H;8RY@?ChB)oA%f%SASt7+Q!BMZvcs z^+3FGY`;T{wI!Jm&RCv2UW9?*?c3o3jFNJ4@$Dl!s{~EMWT)kkq9DqC69HywJ@i8q z2LYd*YM;Ekq-Dlt@)el^KIHysm*!5pz|lOpZX*`qP%`w`@!bzm(cIYf^=RSXcYt-A z;GrQa8zlXYg?vAtbL0XVfJn)WEqPJVTofVnu+2PO{JWLtAi?j1G<8Y6hjH@wyOPEE zk(ny@x%0A%bGE4EAQ7iBjC{S3B^8goNFhU;gW}qCs@X)V#EpYG;g&v2j97w3Ot$Kq z1i)PWJ^suL_+5_5Rnouf{{Fl1NxV7&a4OJMgGsDf*Ubn$n}#|Bt7yfQqvF zz8+Fql$KUdy1NCDR=S4}0g>+RP>>Sop`@i7q(hij5r&XvNTs`*?~eZdpNr*kxz;fE zdG0;6_de&Qlujk1PF6%mPn!KP_%jfQ(DyIJ(MOB6r}=csEeo1P+b_SA!{!| zXBBGl-SYxX?`?**`ugxy@4tNsptT2dCROW0%APxc%Pw_BtC*B@nUMy`l6vU@yhazV z=smw0o5UR4|F{1|KZT@E|4$3R7yX9~$b8j3P@H|e)qg;mnzs|JfMf+i_D|-|04E_8 z3s}FOFOaLsNNdjl>&BgBL%cuwsd%KQ+t^ZC1r&>HnhlfM_4k1|5MV)zi;E@B6EDdk z7(w%afSTzhNR9zezj1tFo2l>*vk?9>wfahhT3Z6^rCu`kgXkpahoRx7@kEwPel=HY zjXod;PhR<%Ao}U`3o%nOTY1U<_U!;`p#P)O&+z8D5%fu%dAA8D>amfbYDT-66>!CT znECsE32$nlQUX)T1rOZ03DjRn%75y){t{gP=I^a(rT$UTnV%=!U|qC{?Y7!C>|r*eMkv+hFj`iV@^XDaRuWP_C4zzs+}mz1;K9 z&SgOrFd!IL{;F>QvKY1`lg-@!CD*2u*l&6m+*Bn{X@c>W)o4R1fZsZ1N1vTUuH2l5 z8_f4`?-@x?{lMQ6qsn4;lXBAAl3; z=E+Ch$=;HsPIQvpfEL}p;MZTHG2iAsEU=f+zRdu;r z>HWh7J*fsLIz)9z6mW$Aadb*{=8LvTreVwKHC$NG$D8=2UwCwUZ)p|Kspa*34fb{8 zZ^|{40q+6?C#as#%uHIK5-_K1KSF^u0DJ^p3VDgSx~11^ynhdutY2{*pA(0CZ&lMP z%wHHVKv4q<(T&t~D5fb;3T!LQ-Ml}g^usvzC~lP+t~P1 zrqQtqVLny9&E3{2Syz7pP)hJm)RS16Jdiz!$Cg*tswC z5I2t{PshVX#~4Jy@)Cv8t%Vs-?mDSntIQ`5)0gQHjet>_<~)>F`GZJQX^DDOUZO_q zK!k6QUSnHrbh`dRGxi-&j@~n+C;aM~?kc6UHo(^|PQ@MSHU)HBhj+zwIPBFSh6W-j z0V5Q$SK88I3O+)xauWc6qZ)O=tU*u_p_*|w!F1HF9VBSd0LK&PDZpLx1&KdfNdDPA z7LdA8zR@v*MG=$CXzQ=I6!^63-&~#D)_N8p?2Qek7qWdFchd9~Ltwgw4gD(T+h0uP z*3<6t58wJKD9F33y1S=ryG$i;D9;LSeRVusoP8Z~pIM`UBXa3n{xuT>ok6CbiGI!% zK?SFLu8p3RLKbWN#XzCLhChc`>vrr zE{DkD%2)gzWR(OXhvzgPFs#DCoJG)27Xc(z3ukAPC=EMET2PWV(~GlQ7N9~J5s;^W z>l+w|?xGJ;T14~qQThr_Xj5Veq0h*`dG}h5Ax~;aTk^Rkfw7g3T53*-T)QQ=yC7$0_bCysU1jE4^ea==dRcP|5T5=~U6yu&h z0{qlsQFcK0>3kpx3I##onMN4sg#mwqM2~{bXhQHn0(6Vvgh0S0#HhCq`qWfMugd4{ z{#}~I#PlnyB1;zi2w8+6FOHqIPK-w4;&+?(u@+149@g%<&MAo=mMAb+xsH8)4qaG=_Ml9Q{z zg`B`nL6|eMu)qK;8sMgyj`rQ5c@?$*%?s#=16MTug#|Lj2mZaX7DXJkTMyOn`ijs8 zL5}QpM>I4q?$f*=$@r=HOOUvbnT{55uMq1*fp@$`Na&KwufKCx;H&!h0Hv=h*elR% zYHv@NwQBC}P6k@!;X6BA?YB3+imdzRtJ%vi$M!CuIpGd;=?T)rYp@3`pqNh~^QYbs z0{`BLqhe5Zoh@sb5;YXw`Fx^lcN`;QkpJr1ECT+-6}66m`&)4qTQRS^#z`A5xY{Sz z%-S{=oYENvm469J(pzi|wDBpz3L_bCz}RZgw*$b3>bg42nFc_CfkvS?fDxj@U@&e8 z4`*!9TL84QD$P`XzxpyfJ;6~6H&wa2kK?L zq#j(`+Ugc=pzIyM(i?;SzoQAuC+2Z0Zg1K83}&ToiF)zuRSU<0pDN*~dzQ?x*0@BE zc@tV?(^H6LJ9(LnwLWv$s64jVdTT-r7%z3@%*w~YmUE~>ZV_F5s-lF3W%!xM4nrRs zoE!;GC!W~-?Kw_@*&eXGc*nM@5fZ>z8ov$dZa`;i&z_P~3x>?gVS|@51JaxQtvL_pGDu z5smy?fd4a9Rz^-Vl_?w=l57G$f*yj)Pn4H=l(%jCeSs7fVCSA0M6$3~`;#wnBl_Og z+|RDW+S?)uQz}JfS?*uBwTaF=X?73D%20 zzk^G*5?Y_7r%Y07JgPC!Trf*mIIM>lVbD`c-iiIPV1P%HNA(C;_rJ67pMi3>6LUT( zB_?^YB#GpNOsdAZM?y;KH_=#YR-(taC>yZEB4A#aAIA?+4!HG9@^@JC$c^UmrKeqRk6&NeEjA z6aL>@aG*q!QNo?cY5Uc9$<=@@6;;!n_lYL58KI<(0 z)AVZC``f!_f45>Qf*5^|14E@fJf=*d~gHt#=Gd$n^07zi@b4VGb0S^WWOu<+q0a;{ViEK{O-IuF-}`J~RAsIL z?$!FcoX*5*qY7(In2do=Q|<4iyPm#hhokpy4(y`o?^=VcKHGPScv8eD)J(L)<$Kma zU)Cu|rpk(@)vdm}AH#bR>l|6!wWbVSq>&02 zm`9qoxv-uV%8cl~5$Wp^=vrg~(}hJ+nI;YQ_gZ3zAZFidbC@b$)W*?+?V7yQS&`9! z=*;Y4jzAKhTBA;J8^0!wV%vmw`J?LbYUh^S+}$(~~S$7DO3C^{-`SH7sOUrHvu9&B7>+H)@J!u)}v+jRokWv4&HdQzp98L zf8Si?lvLHJ^}_GnZTrR>+$!@y|-Ytv5{)E9hFq(WzxX>hH=wtZVm=f%X|rGwW2=~Ta; zg{5e|SUSL^>xYkcelIIyD9Q~CQcWvJWfldVaFD0Fs1!{Kitpr!>%@uiLvw+0ph6t@ ziEob<76OBc0__}U&aj=DI~P2`8*URk-rPOt3fwq7qnk@tnUhP?%ByZRY%-Ep(9ygc z>ZNbIqOb$Iu+_$!6!wJ)_~gy>Go(*YrbhHrvmOB^;1@u;;LP(K{Jlu4${WS^%bid~ ziQ`-_F-N8%zlpfmJ1HIdgeE^tSL@9eyk_GG8FKVt;#AspulWgyvCUnhj+HMahfNd} z?Od;K0CgtR(f-}HRhcqiYSr(%#ip>|F88coZ{=|TeE|M#X5Y);wdk8RLFpHx@eNe@ zS~62X<`^NX8hl`h^!IVm6mvEyn;N&!a`yFXX{q0hlIHRBG7VPqM{7)U8l*1nB)kJg z4mQ6(m~ehc)L_eJiD5tyicwEAGVs=nd|3H-i&3c8aTgm2P} z>B+PSn3RPdp@;jS(vKSvSZ;D6R&n5CvVT6ec5V9SxOK}FdN65vaYOy#X|sX<;0kH( zCn~dvAOSSs7{JC|#^XFSZ{AE@CHy`vCIsvg6{aSTydcl&_IfWk9s$tD&n7fRN4%5nG@*)E)Gd{7es77zP({r8%rZLqLHm0 z_|x={&G}<%66go1vTA=wcrLU;ORNTbv!c#J!Z(0n|D2A}&L?TmCldvf8d zB#^(+Ys)`gwzH8C_~CZjS9!LNIN3PtVUQpL+0v0aBy5LL>5oM+9v9o1O*JkU;wj_Y zXbe_h0c*sOSIbn*{_&a+h8`^pxk~C4H(C5@;+{PrVbbcf_!e>8jhx@xcRV_;yr8Ra zx@Aw|f-cq@`=pp&3brmCUZq#25qBOzQfVRklyy?eARhN?p$gLVf7uOoeDVUDmzB7FI0522VOF;-JZ$3V$8*+`lW2h0vU&>YJqM zRs3*YUdO_bre_Y8u?w5q64l?F1i>|{+)VMtdq7GR9LakL-L-$vlH|JzYS9SVA-Wy< zt;?ICqxg$XyjyJ?c9Qfsl?Stx42932@_+bJO$LO5Yg#(~d3I_O0vIt;4qA z3EkG;tfnV|e&21qko3>Ft{pvkPgyamPE9*+Oy5WcK+%eW%?Q`#ay56nRJ%koHE_MW zMueEP3g?9FhfUrVy^PyWw!xY)EjVy=Op_`kkU@{%cpGSqN(m;pA7YuYp)r#=oI>4b zNJ3*{Vobuu9NuS|hh@K%1*vqHO(fDhY&izg6uFUGVOxeNWT(}=Kry{(z4 zbjlX?&y>ge8TaOw;h|%tFYIRfct`V5jXM3|BL=#WfSZSf_BiW_RvNf6^D5menL&Ky&Sq9iT*@n_gS(z%UnI6{mZrqFD z^>(hq6SuEk5PjOtb@fBOqIr{smZM$dQ86Ew>+M|$wusV~q~S}|{Yjq0FiS-@I}8vP zL4qaTgHv1A`BH&D8>mu+IOmSe+CfO)zsf7kuF?5$cq`k8;T&T1VrD&C^YiOBUe%zO73&Qaq5k zl_It?CYXqBv%h&zb>jQLc})L0KkIeaIo6`%QAA%SU!1E!otIiIq40oi`1>9+9~DZ1sb>#;c(U!;+PN~ibpJ0J%-=>s)MHDRi9 zCokDfrI(kR1iUAYDnN?RSqQP`M!D#f{K}Jb(eaMf)uIEvsiOzT96>1x+;JO-%I|51 zx+YszIEVMeRxQV65it!AFYdX@is_FAi&WbwL@!yNy}Y|dlQm?&PZhpvyxUQsg0xe8 z=N_oz2{A3u*&W12l9y?mHHwqAT8`$ZN_tLtRoi8v3`$*7R*CKO#2y1Cd8dKVoCS@U zIX`vTE$h{TRmFq*cRpdpGMZE0*MVB}HZo$GvEj<$6^9Ru&PGSK;RE+zL7!IWob@!2 z=6;B7I#OyobZ|vRtjLwmhTGcpt#R_E!-D0DV7~x#rdkh&dRq1R2->yBmYJ&+n{h@y z74_!p5pP>vP&Eg%koDB$fWwauXCVz6m65cE=h=jedPmgq^nR+vQPME?Bwe1Xd50KB z=kRsw=v>tAnd7{nfKy(c2|zo`gMQQ@nGNkL@bKX7xQSRvo~s|ZE~T)n-fc&@yD2k@ zJo*6qlYN(!Gr zONxYLIq0q!+nE${_*1@7Xx(>22j|%#qLMlCdN?q{jf(I|8{LX_!_Zwm zst>)erjYaChhO;V_=2JI>2>$*#exiU7Za-XGo9badgss|uYSd!bRB^z zIUF7{9 zW_y-VTVb5LPjsVd>5@ld<{vK1H~NKK8Wi}o4cUQrQAV!t91m?m(}^>@lecQT`Xd=y zJ~1fwEG6L}nE_ahx8cI;EC3fcsfM@P<{sIeC8L=SM>Uep21U2|qmJyBI{|(%243F} z^jSLhJ(K22y~3hj#bs2bN$+IHH85&Re!bMxB7XUpv~!!QTv=G{dl}J!+tJnAxIx_< zgjBe{<>*^sV9y?Mij2S>7%_J^eTgC1!Qs|Dl+7Oof8)a6W-0J zRM34YSTMpy6~%4Pe@jSIW1dNV`DfC7Dt59&8M!Dvaar~FUm z7j!?Yu*GZHxgTFP6!0c6Jj7k#m$}d6PAM0Ej;cGwe$JTLJ;7r5^- zW$YIS&a8n8?@K%mZ*s9%T!f|oD~a*WKmaWYzd5lLyi8F`;ex#oCofG?$%Naldy3^r zPOPf+7rI@(vZ$SsDwm?>lC1pG$h_b%+FFJ?c`ft}mSwV@yn9*N4V=mKV>`K5#FIQ^ z?q??3lasXa091$tU@ma`sAw8a1>CPl)_GIQ)>0QkkiD3gpX+<84kA?kdMTJr%n4DX z^)Y??^37{qJ{wrl0MVO(<1I+)*2oW#fnSe#&r0b|Z3k=&V$-&@xa~NgcVRP>hg(_V zFV}(Zu8xx-39#4d5+cJ6jv4Fh3k{A#YDDK^zF4IKh#shFHu9)qi_jtt36xB70nWWW z8APhxdYmXC%zd@4rFk;CaMhD~Y&hWf!?+>jKBar-lG`UZ`r=b?@crr9KhI z7Qv&f*jF?!NpR34XrBY`Udsf}TNZUVrk&kr(Ldmrj0m$oz75mhQ9%6BwA z)mXjOO#_xucqLAUHVhzqp?v?*{rBi@Ub3Y#gq9;wb${wFzl6F^7i|+3M;cVU@U4K> zsr6&t9(00bT<|4H>~7h!MFN*emmPMt?iA5MuLuxjfaC&DIb%=@Rs4Y)Y8V*ISaBH% zK**!`n*6l60>$G^*+noZ#jlDUNEC@WYl182j(j9JI62$)no3GQ_YWWda#>^zl8Z~g zh!d8AoJ3h-OaQny*lUGin3S7Gw-L&2+;_t2^f|viNbR#`wxG>NtVxLHx{hK=q^-H^ zhjn{pttD-V5^wfd9ZGFyp6CTFczyOZ$nI|atngNl_FKWQNy^5np_Scm;CiHZl<`NVE}aH^oT zAN2&F-vitRMK67G_6UerdFfC;=IM`BN527m5vsiuHTaouDkLWT3&E7erw@FdFCqzo250WFL!VO#QxQz$jTsQm@$Df%R z8~7N_8k9msyB@v6kIYNjIOKDLUThyhid2~A2aIi7R229-E_8g`0p3}C_dO}PEV@6U z`w0ep!)K7+O@eF2DW3ql0enouOSv$c;2xWhax!{=mWFnMpcw3UxO=_zw!%I>;Npn& z=6e2?7WGhIrWEK0!ay7X=pFSqlo9)~@q>pnpiO*zvD?sm7pR@Z2&}EhkXVbS|fDM)NN?=)qZMQG*Gr4Js({W8^!;V~9pD;Igl{&p^xrq91eMckg9tEwOp&#^y*>8$ z_}KG`2m~9l^x$;0Wj@9?WHSe>m`_N=mhNSaQmKFQ`KGI^kfx>2jXxclsUYJuyHjam zXJXa7JzSGcD^0d{WOLL>uEu(rBy2;=Vrv7qpb7!a6-A)8vQ?y_1w5ZU7n-9TUioKq@ z(q?>VGOXc1y8>?XqX)#09I3pQ(FC=}|7iih=>vmHf#rcShz3cvM7>*oGq)mpOSITu zuB9ykjm@l^T>NZ@4(M(Yxt%m|Z^*={8X3jKu&hMgG4#l3Bjo*{R3AP(q?Q2z!hszgm7gGKT2 zsEN9$QI%k>;c84Tps9iUg`of#+=_UBCx|t8AC9fmaL@XGRQ6{y2d(mkubuO{UlJXA z`#4pTc;%j&=viJ~jp*Zyus3h{$`s7sJjmpX(=AGpXCGDj#P{XM*!Bx`StP|g1}ed) z{;1jc5$`XXppq4CBuSx(2S~k|ifZXt-n2h5gnuazu$R`XWgawcv=~{I0GyF?A$c|4 z-0)Nk2i?xjjzLZ9w|8tViy0+$erszT=!(tA%v}8b=?NHM_3cTvUkF0#lAyG-6et0J zLjaxO#Ig%uJXa5pYkf}awiEJ&@5b`>&E02oU*=1Zty)w+-Pz(waw+0BtRGx)W70x) z+9_vt)QbAIvbldfBTe1WQu_J@mNG@#xv>^unfZaRKZ7VK(ug+QhLe4O-TV0sq=>}<*bK)|`&%MKS8fTM*DT6QoF98S%g?4WO_?DdX7RO>5 zxIEeShkdV<5*P^N!pw1ccuX$za&uWgrv-|a1mvSh<-5z%-A6d+sf8es0+R2X#BMMQ zhL?tjF-(RsV)qOQzTfEK>y`&)9Bj80wg70aDyw*da3f!LHc+U0B`J;m_!7T#@`*N) z$;S2Az#)4nQg53uXwE)ekG4$fi}xxyvCM7(wz?~>2=H{CFL3~85TT8V{JQg9&k-QW z?@~5fcDzKzA{tdb8a0wDC!QXWAK*q_Rc5dTgkYESH~nSc7$6iYQYx&b;=5l<*gy;0 zxgTnm493F^z=SWrq%z=u*pptUn1Cs-ag{rvHz5c##@>2+D{p|H6m%z1*rbEIrnPmB zKS%-kx9!*Y>9fy)I~}jlgBOR)#q2ToK}OZE%$pPde`NS^(5f!IO{Bw+1#e}YAa!fV z-}=t4vY$q1vvg30^dzc^Ec5NPKFa|KTYPno%jU0sV9O_sMpiKK`U=sLCGZV8LK1%M z8{wD*W|%!#P5p)iGLHa})Q3OuW(^K_)Lf1v@g?EU7AT1?;Or^B^QsdvHWIG4iA?DFeQ6?Ua{}suF<(P=3+fNB7Nh^ zAsVUXw!QFcGWv=F2CSyMQ$mlt5I2%o7--KLKZl1CgP9e6;ms^jresc=&ChAzK+-J& zM!%rs0}|dYH~UOV-~xJJq3Uf$m_Ip)0r#YBlf9@YYPoV&H zq@$Jd@g(n;dsBEp%!qH>?V$r%82#~pzVywbEIK3waLHkQr@$cZOZ-Ilas^vfuVgeW zTt!9(QSEsa;m3*{wwlU-For+?e~pSksAkwzdTCM7F4LO>3cuUy(@MJp@HO<9j4b~d z(g_l1VJ8J$hI+`0W!C?hpUQA}dHjbX|9VnKzVXk!aHmVwn5i1^i`jxC8>4wE&*N>h z%uEOIT$R>*Z4?0DD_5AXXOFQ7z0=V#CO09tf2f3l20>X_f}KV5=(T0IbB2W@>2lZG zpq73vp9-bV#s`Q3SXk(h<1^Oqq$Dyh2p6b>CAr24YZm$jzK!yYyGOy|=s!F-s z6MQ=D=JuY;=EQA`MpTfC{XTN7(D5)S{UQcYDnk zGaL1;`B9U@D{?}2y*J-=P!os9 z9vi}gE!Y50I%{y^1bD>JTAUecM!Y>fvnJhc6_-9SDv$R zvoT7Mn#w@C%YXyI7D!g<6)e*q|EPIJDi4~Qf$IRXC_(a2EzB5Zay{l-%z1lonH0W* zou%no^EJx|`0&EZ?LT(UFUt;#q1D(dsxZ3nKd}G~+59?&G;*uJVI(f+}eaVJy(JhPd zy9x`V`h=jdO4pF(QpDR;^}UTF_@BP~XFWVsb#-AgjgH_(Yarl}@V_7h>X0gXYNZ5_ z=k57593C9-0S(FGCHJ{}JorKYKNB_P@Nkfo^Iew8>=KoOzDTz17e&o!1~|VNGfP8= zf|NUIiE&;A?+dwOdy=OoiZ(~4t!q>@iq#>E44OC37?YBPb)~QXx>yeb=7-_-&H2Y*(-U;W4?ErnSvU6M;Vt=Q`R~5rg%1$ zp*&HxV;;Ue(`Y^;1m;GAi+u5B8mfW#M!YX-B_Nchm5YT z5#KH@H!3DQGr{U9A6lO{$xGwJ4gw1bj&5_EJSEt@ug+Z11VhB8v)QYjmp|?&fwCZ5t9K2 zJ<&4Kq47gy`vuh?4f^qi(l@>XMEcKq6J%BJt*!8#zphqf3%*zz;j5pmm_~sl+~P@ikR^_O1VHGIj7dT} zpX-iS5kwYQGlH7_1kMZkl%IGLnwI`xOx^eH7 zgH9nLOM{05a@soKAbA40y9AgHffAmyam%WQ^0Kma8cHox))Dp}D5m(qeg62A=#@MH zUZCAHZCGk+3N5FB^_fcO4t3VBiOrX_hVT3fXO4B!Ev$EhCEMnw3pOKEDwPz2^eDjN zKK~eUBGp2^_dV)eti4(7>cTqDH^dWiz|Vq%nML@BR3`?h5%v;fea#QdYPpH`uLb2}~d}lEnd?X-i;GbFcKxvh>p3z%z{Yn+sc% z{0z01OCo)DrLRyE)Xb!^9}&m_zxSdjw970Ah!`KBv}B=o?wZY{6xPb2M}_-G^x~P-cR4!FmLu)!`}|^0EH-Yo z%hl5wM=>%gxKxDE%tsFQxMjhw%VPn8oe0v&2WQ}?N!-19y#C%KHVVUQa}HZJi0V;7 zms29hqj4t$aH1Bj8}w6ut2DS$Q4zG~fC1qPsF82g_4V#1(_on8fyAAmK_>^@e8>6r z7$5)x9kam2EN9=IXAf^4gT}KFf$+rp6`K!n(EZN;qyWJpXw&O>8w)nFdOjWVnS5#Q z&V9&dy^1?Bw_H^R1}%n}s=;=1vGY-bZwi`!u6dUvpnr|m7Md%QfjP9WA&vDKvdr6f z8V%F9P4w_xD+<1xI$cnU}H>k;O$0G9+jgX%I3z$?kJ zm0Q)A7iaLOB`JUws^UAzql!=9$f}Kg1GjP{r=$P?A}UuVYqfau0l3yC$5~HJ!~;qZ zyPWZE6P!TM+yZ6?2g>N^6qiJ;^eW-@@PLtuAq*h!&K70?$mF#wM7{aK5=#GAl*Hf*;(+Aq3z0~ zgGzPG6^tDf8a0vCJ?cJN#Rs-d3PAe8gte~%Y@0yG1)>yiKw-Nlg(5I(;DpXR978(! z7G|&|RJs~%o*&=N89qk{iYl7&gDt~n1U*zk>&BWJo>(0#)hJwt_`_4}^)ZuC|NQ`W z`55?*3|SYq=LPdq1R|GIELuq3)*-aXqN>^GDWI!KL(@@2r08pVv^ND#A5C}K-SN57 z-F+3`Anr4N+THs0%QVr-hZOD%_Z*6YgHr^srA$L(JN_iV)Ut^b0+kJ*B(0Q!>x!ND zRDi~YH`XP(hd>a(1C4|~KcSzdNPaVj92xuIdv$$n*p&QNEzu(Ox&O=4rwuk7LdJPH zM){<%n|S({4=DYV*$3oh2?q|snnPAEd_Jzlmt%O0LM77BL`Ga|IN8>PXrMdD#E{L+ zLKU@sjyMN?sF)EQvYm1e1{Xl|beMsNc1H=PQ}ccmA&B|_B9;QlcUG4Cq!j-C7DqSB z4;}(nZTH}s3f@Sko zIDOE|8~U7DrNaWmsUEinR(6AL1#D(ibi3n)HEA>K>#x;EHP2d_?Zko#RN9g4CiOd- zR9>#gbu^E-iW#WSfSOEYmpQ0BrPK%JtY_4L8mN7GYr*kS%Z&!37+fajB%t>3w_r_f z-?u?lMQi4o+z?W9Y&|d2zl2n@|17zjHGjvnThO1EU?HXqnRWE@SJFW{pjp#uLvzdO z*Z5LX`D&&0$973OYXd#1@FTtn-+I^S7U+aecNhsSXzpyUW0>Ep|v@_g9}K&JCX`#jc__igA(v`%AKsgOWroXQpf<(+g&DOFqX=U zMMsCYH(4ZtTw6Lx_z+WpF&bZ$6qa~(eIfT(1v5GD2w+!nAvS6Cjl#QudGor#YQko-M5|2(Slw18v8)WP8FSTQDxM`4z$dT#9^{tTJ~IgBVc!Euz6kq0 zE9M_15ss{04QN_;igcfjy8zP&KDhER>iO&QP`z0=#LVSm8lWV~029EObyfvh1RD)=+ck6Rg`P%20Ae}ozRDs8wCFo~7R&~;d0n8} zP9%0xm264ZE0h*N(Iy~=c^VYLLV#DUso`CZ#A>axH_=_|mshr2kRPF2ofut}nv32y zoJ0`T1xx;-ZBH_(Zy)-#RWd=#=H20h9AjU?uCxLWW92VrRln-t@Xt&DhtFf_0YYm) zVF8YBpQEeMmn3?bCc7N_%%>Jm#K3*LCcmuO3%rMVrRBu-TKtwnY*jNwW0t>slDroW z!d(kOT?+MTic*AyKPWVRol2B-lNc^o6nmfIJu|y?#lbqHLgFO$>)X$D&CZUYtuh7Q zo=gW{Sj)3TLmVGd;C%wBvuu~>caHXsttfyHZc3tekfkp>K&po&SH@pN4M;38Z=350 z5V-*lWP?JF?!3SKzylWJ*c0xuT4;MpHkL$JqyyIU2P2KB!JrtH7Tzr0G#8jD=v#TL zSYh={FKM%Fw)wk(PF=y$NdDJJ14Vij>mcXZ3RPj>6170{o#Spik6OK!v>7C(o8?;V zn2@mTplri396T^~-hF#4qtgJpAN5bDp&;mQj}kvQBt5L_1TQRbHyUW4W=;3wQv^Z9 zZq1si+`j7B4MDLuz_G|w(x_-P`Uu*{&#bS@WHhcGeBIQUOa5T3ChUyVkbrTzkxp1H zsdWxMGF+@EJ+b7#{Xwai49 zo_kD|HPBU_&D@YmXGZ{}@O=#U87M&f}Am^h~vqb z)m?XTuAl7=$~{j6me|wK_nX=>RD)lYz}?sVr&5x#xIG9wFYNjGi{vI?e9j6fA;Ol6 z16P|?f|ub5hbn`J`G&J&bKv#fe>rNk(dw=x74j8$Xq!bYg0H2TOVhH9Q=1<|ir(-U zf|jbBQ(-G3%+H@6^qEQck?-Aqip*beWw&ZX29+I)VsE}@axp8Lw@Mv ztRnlbURsY$lD1d--HP_77D25x+WND7vTTdOw9(B*1a*3)Of*qxC^5PbyOcVrZjXDp za(3B8szV6)9n~coX<9_pgUK}!Y*l7+s{5yU5_W`sW$tr(cdNGamQnT{4fT{oQ{I&q zqRH7=t2QW*nh?k;<;tcm*U|L$st9%G8y^@Thr1833KY3Ea{@MD()$@&%Q&METU$*T z-1(mZMnV09Zjt%p^74;whyDx}y#%$!!8&ixyj_jEX^-As*7_63l zQ6(L@zYOjROzC@bo*ZJqcGl2+du)c~k62>3rgH+t32$FTOD_@9v4o?TqxC1tGiz7> zux+pM6`$Ntx6w5YLYou!w2kZO-d>EHv8`6zZPujp?01`1ef4vW_MYS?CcgFtO#(B# z#x|V9#_rcX{xm&Bd#7zLW2+Ge;6QEG@;xjc!p5|K!&d3xW8Y*Vfk&GP(|{rnorAK5 z1%njS83p#IdwfMJ*565s@eP$6L#k?uGmJQC3Kf^s#t^w3oDwlJw-4*+=cAm>G$!1rrls1a(*n_4jSyM_iUqGIo%If?1OIo>J&-O`;fC<4E zhz3MJrOGE1p%YTpXlvGs(MPT6vaDggYF8tsC7!c{G`R7%K)2=rYvAY?%ggMkL) zcXq%RdnnukniQSw++73ptAWkTg}-K0EnEvoQ_>)-XGzx=a3RY@_j0|0<&-`@US+8i1lVhJ7pvMgxQTs{GB^@|( zzKu^f-z1R1dxFm)gkMXDJ5yEl8;w0UJk|mnnUdz`2@{kGQ~;A}Dhx?Lw}sxxDlk*b z;=DHcXVoZlTaw){<(-jKOb1(S!)JpuO|4pricQTujuFe{;a)3igW0)`snE=Kb$TsS zXycfFthn8^4$8|Kj9YP$m2Vxa*5l_eJ$jzEoPyIoN2j6$fXR7HkoSYO3z|PDWj+rl zLqR7BGnXO!A@Lz^&M~s18Q3nRuO~T1;fVQo>yiaba@1Y^so2e+XibsmvYpY++mezQ-8jdcn)-X^SscnoMzD!yqrrHDhJ8oR%ucO@o`{c>G$VJ z4h=-P(P@|sW}8-z|M|VT+)57j{ZkhL)oV638u_Xiv_`7L`|GtuZ4wYl_hflc_ps?*JN_yFUTwbz4&(J>ySduKOyPbdt6g&{F`+1v1*( z`4gP%%GEQ!atydO50m@B%G8J>sx1KJWFO@cA_`TQrwZ?AUx!PMUa(Mb>HX=g*_S{c zF=&w%hc!+hP95O(uC;|NUTNF{Li{X4!YKt)$zO~DT2`k|X0WYwMR`f$P9dIomUvQTph3>gj#VEM1XVfB3(fp<+QW)a51k>CO}@NN zq=1O+gD+HEf*iG1AAHMU#7NAIVIijz%2fJBwf>R}DF@GK(aDikeIYKgK^6FUqeY)X zbW$hCm-5Qql3IqBmBo{xiX3oPYz)4HSXNIh0q7i1$%=dm@2j!y8i^tHw!GN>*KSe` zdx`_OAD@%Mj+yjohPKmoMc+CFQO|W>l0@8wd({Ut8f|X+{AuQz>CAef-As$Nn%A8E zb$mbG>Q#|>%R|ZO!lW&}g0_hPLe4 zeVIcQ=<@eYd#E4_Fe6E?!jLaax5#bI<=t-7A#M>38!DZO-Ki?4PHo%r3-~%>x!Bts zb)2eOJ^E#CS7IckXd6CCB`Ct4>mk^}`qFX5HqYVIB97z2c%OL94sydr+x7O6E}iTx z04ABh_0vzy0HiCx1Ulq6SobC}QN=fAVd@jCi;BpWe(n22PLZcG-{!+XUd!vjZ+u3m z*=k_1-R!WcBWyY20cpAyGydZt8ye#1kHjy_#S0g@(XWcfH`^J_QE+Rwj^`hTwuwmx zi+t@ToIJm9;sXdrtX!{=5T;uKdu%-ruw8g{9S+LRmJ0IzTBwTomxlNw6(FWRdzJUW z+mM0X7ASx1vgP$R#S}l_NlrY=HuCNe{F`KhSS+iYL+)cz=fI|$gb&KghH3+nWCZu7 z%YLD+7diU7d31$&jAd&ISS~XO-mg!zhM5j03fzN@4H%u&YrMuPZeAGvUn^C*TYL&& z7y=gb>@)G|BhPduz;}l-aqq7&0Vv6JOYPN_n?R_&BA`V9Nq=X(@%_IZs>w|pNee@n z$^%0^M;Gih^~}+%b!}l`k`QpI-I|4E``%X>=HK$qSFI54qd`B9Adca(wT-gxI>1-A9CB~W5sm;P~ZifT%bNPX9w&y;9u}jEdi{89bf-4UAcZDu%pWKK~9|sXY}fbf|#vd18i_{ zm_?qpwz?epaQ};SsK54()Ta0MPHAn-?#nDHJEM^AX7T5rp3Re1x5Qp*FhHdX8h=? zc>4%BOCERRw-p`YRXc4rX&@)-$m*7Gw-U&>5tcv3QKPqQ(gj^-M;G(+*|A*#^Aiu~H?IPzf zMCku%0r)o-XptkC-A~+}$u(z%3q%1Z{^yUnO#4i@jF&9pUS|DrU53fbw=$~Au`<<; zieLkh22nTulP=H;z=z492(Sge>bYQ28J#i8cT`|upqZ0W6UcrT+LY)% z&#+^h!M0L6Zxnu`(kV_Y&@)Y~UggmIzCZl2r7Yx)@`Po}MZlErtLW<$(7|L)1+a?- z#KW!Fhxy)-fKoG0{k)q7dj1NPVlUaHHo|wGgxm(U@%{79787X#Hu6(Y^u(u@(>D+x z_K!!p;hNf+Br9CJpOGAw)zsSu%59UE9zo`fnNa)9kA{T`$WEB#B*Ijh8%uc4st5G4 zI))MlVVbdq`}Wh_tk2yy9__q)N9$iMqpAV`CXiv4tlw%64mn2r&)nRt^htBnQu@rt znALTfYa8jnxJrtaKm}{i+x0W<_)lT*6czDc@#|JaiU;{r&7`wvvzEwWI|!z&50>v@ z^XMr1XjCA-^_FCgItSq3?&@LySs#s-IgRDn>t_ed3sw%a!!j?s4Evte;-8kTdp zZm?uULoS0(G+O+j=yUdZ6>6{(FZK`0|0R_pE}8|7jd%LzC@i*8-u$R7z!Zx`Q&9p! z3s8wPFlvm+XpDijQ&3;8bA+QP*ARP`yJ4k&0T1AQNfbkyorEuQVfXhWK1aOv9!d5S zE}hs<4RIG6B^)Sho-%lm*R*txGm!N|*31Do0zmmVz0Ji5p!))jm}xt7#%0A9}a^dU7?B_9N88fYJjaw7(CJ{y0*S7=g)kR`2uG6f@Y@L zU5Hgfg2dVkjl+ZDGQjJ^AgF=qLzKMow`15-r6^LIudrT|%UOi~X8NSC{aZEywP5-e zRikv>lQwcX!7k(7vZTzXb(39}y_ETp;0EP4${Iz4KLxY|?!quTzft(+Jqh;u&wu1b zW($_Q+=$JoaU!|#e#Eg7ziHoOlOmFyb)T&@)W{SHX>A}W%#A$I=#L967Y`6uAN9Ww^}X7y_vLtQO%O zL1ZgdT{VrRK#fb~76;n~T!8*iOj7q#uGLm+E13#9qt&o!Uvi@Wf zJ_wq)$0&X-Iqfzkszq{H&tKy`^`p+)p!s2diEwX(x;)k=$Vc@-eHLqu)|QMO2iy0^ z6Nu+YGx);Usolk<-9;PQ_iqOy3fWll3Eo`IBk=$C%$o%pxpIwUp7_Fcybsu+F>qV= z-Z$m1ekImIJ~N8tJx;yysm|z?cexNMmC(FKpgS*etJa3(*!&C$QA9Y_Ijph5j`}N9rgHt|KEbA$n-Zw6k#IzAMjuKRKT!WNWU|E_xbuMlY6@5)2NXstl^sst$rl?sbtEAaxJ~jO1t*sYm@#ukonH1xw{;!9q;QL z&tYd=Z85V6)v<9u%|zP0@}B<7mk-3DX5SJP=*I2z9zX%fZyHU(O2~i|Rwsvk_=46Cd?*!dW#)H%C zHs?d0uYakNTK#ti%a|tq+^F)=VW%dec@vw;Zqdytm$h>8(Zz5RiCrLJ(n z`fLjrnYj4UW&4G4t+tmt9lqxOUiFBaI+h9^X-vO&nj)LltKdSyuZkN*|bhnLBmaW1=LG9i7m(nFz=&ciX%f8-G0`MW~%=JTKq zibahJpEcyH)#965(G*TBW<1xQmlGXSA7AVdzc+P!&xt5E{vIsyJdxj~JQhtp6~V$a z6kc>jgGpTt?%!BpsH`~6!VmKQ*gT(NPn%G9 zmTT7j+dgrcAi*6?JRF`TBcCv{_P~4&wk#sq%0Iz%Vg-MbI+Ih3Ii>9{)uEtGz4@T7SXqPTB89YcJY^#*;(-|uF()IuI;_R@ys&9T$pTu|B z0>!TH863owji{7c+(ik*JcNas9x&DaZdP>v!$x%-{(l$JINO$8GAVvMcf&aM#{Nz9 zKOj?Boa?jC@0xe9{xb#VaF6l^Uxkvx?9_$tZ)_GkN(EERQ#m4IT`%KVJ1>-Dx^h)J zy89Pgl?<-FzUQJ$mynT>u%q4;_DtJ|bm|rV!)&%ewzs^$Z$646^vd(U2Jo`5q zU=rW5^&PekpW%MPIw_z-BDVhWSIbA|p$}KuKRv!$=pykef>&as-fonN^ZRt#Zq-Vm zPJHQx*)h73cJ)1XSiQY)plKxPDEJobm+KcwAr@s>Z17ev(J8Yy)sT|Jc+c;&3a@w# zW>+aB(SUCp_mY{e6=`5pL2PvMUL1ceh2|rJPSQ)l_wWwLNQr{hd5@?Q{d^2fzNNV1 zF_gT`8P1@JnGrqL{eGnHM{euvxGL?tywQ)kNvY?J^+m|)JJHqNc|pZx^ZW4aBIY;l z1=Va5ii}A2ZS~MRDfAk>HGb`mS?e{_U#}o5RWo$ho_vaNXDL0B#hJaFp+Iz?x!v`c zbbck`$EXzcXy$_N;yOy2Txu%RyplqQoiqGHnl5fp$CP;%N9|i%j88c>;}p?@KbP)l zt1G2^7Q;^y!2djiuYqSx;_K_Ngo!P2eiJLXnz$$bVv$jTnrLlz-5kU%aY4{KJNt(E z^Vc6ux2NCSPITJ)Z8_u8EpqA{g7#`o%fV1$D|z(xcjX>CF3q$ASb`ob@XtN^4GOtt z1eXiVBu-7$^e0=RDgQ8emX*ED`KD@gK&%-f7S!rf1Bj@^=nEh+SB+xx*E?c@dRBI3c@pz%o#g~RrlbkwXwpWIB!SLI9|yf3kW z<*ts#5qg=#V(I)tYxb6(UTxQdpJy(=|BUyv1f5HM&#Cp&FFz7f@(fs{!HcG4*QLot z;H~~FSspYXSkQfQ_Y_0G!8M2R>QjaTYPqU7^&oTcw0o|5PZN24J)?Iu3YF}Hryg{Y z&JHIfvu)7t$hj6di>u!5DyDBG(PiS^G2O>uB$B&a{GF0Cq<+0-f$PCg?w78}7*+Kz zrKK)Y_czNg3k&HRE3n^gb!li}BV2ziBHjKK{LoU#V^5RFYdW{R2#9~Wl2Znwb2T_7 zWjE^67USukLEzGEA(2yjy{5R=11EoOf=8$zgVUXR9MQ1W?8?SoDi~~ zPhEH=<;50B;5gPR$>h+*a2~C9Df-fL?{%ENUnP55TvD#9tKyqx9Cgg~B3~f~-*po& zUeJw;g7(q*9}Zb(TEFpb-drlX^_3iN_Twq3mk{d3g@}5uL4)0hAYT#@SI0y9k*^>3 zs;h1w*6sM}^&?Skynu0~AI#(#!%nh&ykZ2esit@hsIWXoW9}OgOl2B4e zN!&<-lAzA1VX zj;x)4Bl!gbO)}s6QIXQlw{UIbB0D}^e&vhzZv0$BSpf4-ot^EbxnQemf|00;i6K)J zxw(V4m&s*46ZmuZBhB!{?@?gsyA!I3hCXl>a;Ce}Z?krP&_5GWPZcaK!{!?;pX5cN z0G=D&5Bpw!3)kdFh!fFSZA!kmLznJRWW$4`IWh?p8p6?rkMkEl&uy?JcECqRM@PCu zFJ!uUG&O;j2$UXF#eZ#i|2~|aHV5?+GXa{09Y1B3jjFmpWE*ycW#fcgSMRNHy7|aj zmWl8_mE7k}4J=1P^x^iO^`&1%2V2TG{32Xh8t6%|8&qAaXA0MIYak`q_n6t|(~b-T80o3`r5tI!I1QAaSMl*HI?OS4GHFsI)M zBv=fp+|Lf=8{Xtj^Z|*fBxNTw`VlBNrFtr)&1H-%n+enM{mpoXz7oCirC`esFLF@S zZ05K|j&iOj3!|Wm#_Uc~4U(M<{*2@%_8=SGvh@8Ir908`|*|wOiK)5b+BT@tUTp+r@)1iL|XS zUmH5s;d4im0>T1xVFu?fvc)Ui(Y(%n=->0w1_UeHEbioK!3;U&KJjakIeiNzuCC|P z=2EGP<&f>MIn36MX4#B+rcc7^oaiuiZa;6C_Gx|?#gZwf|3|qO+qa~7aUT{E{)m%) zw63oI{87xXw1?W#kg9gmE;s-A0*$v#;}7u{RP*zamFws)zMK552ao zhZX(4p;vP-G!(qFM$vb#x-a}f12UrVN|S%K7Qec|yu{1#N(}-kpxh2)i^s+c#l1HP zkt1Ck@i+3cf-QB~$WOzWh>%I`J^?N+uKH4YkbOYj$)Ug0-ceTTaL!LRycik9A3-rIEt}u z-xG6=E7DMWo+1`fe!HAl+A>U%;52EXbB@l{EE8*veC^_|8hDjijH}cTQRMR#v~x7A zlS9#>XZr-M(M0|5qOaYZIwS6XKrJRF_O9PnSXfw^J2BWM`SYv`4^bV=r%vxq*9l46 z0<9yYsT8pVwBh{|XoeArB+84xez(qXtw`#i!op!oL4ehD+R8GOP92+jP8;I(2fHQJ zTj=+C;x{;biga~L@n^Jxl&{b?Q())qJy|mM;^|~HQslTcby8v3~jWgqsNokA6C%j z#OGsI%r2Z3#O&^*%pEcW|7;q?Uto)fB?!E~;*qAz0w-wG<{C7y5_odM7mo1 zTc4a+&#PmULEfe6Ne6oULm!{`pL4zN+EROkmncpO)J7`vZ>m3^*$-|&by}T=DW7nz zvZJE|-n-N=47Ef4)ZU6pNqC>EV;pm zqN;)&&PGLha_j!Fr;@#+7C+S;iBTS959@b%$GW3&zUE;CQLj4rB|_{ct>!0FCn1|r z?t7GF1CJ|1`fA7yV^lCbKTml3_U+GB#cY(3PPG3>p?OPYm5wPZQm073Z zS1Bqn@{!2)WkEbctv}`hEJP!3lc%^mywtw8YK1j5sb5^RG$~A}p~o8}P@r$PzrTM* zJx}Xdn}yE!UyL4iSB~*JQQ<>cIkRRFP3+$}(tF7|Nvg?-Zq2{822bF_1NQ&4{H)GM$ zjENmrE_qv8;=#OW*K~w#4fD5+I2TiTS8nY(Eu&%D!mnkV^8tGJlE1?0m*~3%xE_QB zO4x&uN|Vk>b;nzK2f^CAjP~y^1hVZXOsKu> z11nd2${nwy@aFE^!LO4malabMvdm^l4wi_t)BCxVB~ux|)m}Sh-cxS(6%~3`orT_e zYIXNA%DylHE=fFj7)#i{5J5N{ZBWvsdNKZe=nK=lBxglW0~+qz^%u(LdJXVx8hM{8 zy+O`+q#qy5A*YS41(a%e#JomIqriBTSsF?It}4qNfx=3zRzndv^*>i{SGVTtMA2_$ zMYYS*6_yPzhKE`P5ukUPj~>X8_HaPf47`;-p`HV>?yy)gZZp zG0%oZKqc6I1VVE?0fVp8IM2z$g&BortB3`TR517(cja#rU>ZG+6>xuUm%cC@8=+zt zyL_#9cv0mz->S(ci(lG7?n`z;%)u4L#mF_g!9ID*(c2P*a@@M*N&wAEKV`T4%kT zE=OPd%0>3&zA=>{IO7xJMhCG4W@GcpT_{}%>s?xk9ps^VGVS->uYNIdWjr`kr-ELf zd3?cCKUZrfrnx&id5|hkf67$Y>`THu+`E=N^<2ell4|kO=bUCOo@Sj1`AfWnaT5=H zRF152n-=kl##YOf-EZ`C*lO5GPNc&Mt{gO`^OWW#_bFh_*xlcL#)jo_+WAGkGJ~qR zcTlN)|o4#;}Bo%jWZd`0(m>vC< z0QBruldZcj<>d-|6_Y_SpAVgzXu*=ybpMYo(j3I!-6hlPVHnHZDT#?qEz`gL6SJ3T z9he_c^TkT(%kyX!Y4Y%xI7SCOLGsK(ZvwLd^s%(>_!y4&W3##vE;4P6!lK-yb^2c) z+4j1=%iaey6>+}EzIdCnsKJj*_Kkm2XxWYX?he<#!AlmT>r1uS;N#?MF|kaP<)!~P zMW#Pij_b=zpTU!MIie}s-7#SJV{Xk=t;~C~kG7TVH9PfPTr?T!LpW>bJueim$F@QGCE6v_`5?LH;ZvwrZP;#?XB zmg*_suyBfpep+hLf9MTt%d&K&`JeB*t(B|UQ#j(3cIXKteHn8bR8 z4_BJ`*9e?lYtco$emRA*NG651oJ_g*DVzP5G_H-`OHF@&pp{k7=``i6|9$8{DB~aJ zMb?vZw?z1}{1gE9oG%r#o^SL7ITw{L#{^{(+wc~5V%S65RqyBBdc}*Z4Z`{UNds6eorCEeJ ze5f~xoA-&B7l}TT4oR|^afv|*u{_fqwTCv1MTMN(=4vc`72lGw346(8!^`iTo4BVD z{mr}cAJY|Plv2)LzVrt+zj@_3f}b#r%Wi1r6}#5E$M$6Tx9AG9m$$N{3bLg)3aN`J zJf-(I?u1`_VZ$<2p|_d*Z}*bba2H*BkrmNDHMf4NkNC$SPS0$W2c!Ib2qeEg+G$YY zVaz>`QNq1V6HzRf>7Cbv)Hd}`THV?CGi!uJ7g_(?X6W(QEK3w7+nObT18a}M!5lFcl(Q+e(^vPVVW>3!v&xy#O}^rM>7x)QrInm9I@ z$yGWIJRM4WaKABN-I~DeR9Ux{z}Hg?9FxL|PpO~Um)^C8vS^A z*RD+{mF6#1O4gI2sxIp(*oQ%nd1%50}9E-%j+4S(D)s?P~(`8bmF@J9M3{`Dt2wd(c2)mP-9~Np= zR4iQOT_^D0gO)wBije3|W~X^Rs~xmW{B`(TOlFnzG#Rfq*F(2M$q!C9#oGs(C)`e> zW{&Le7ZRKQd4x^DyVp_4)bWB?$oOA(qDQwzs4jUAVvm|%9+7^dS7~Yn*QA@dXmiy+I}MM_$?%w@oc@jN^hk0$gY4upzeG?vjnA7iayp$CKD=D zW0IFr)`Rf>%#5j*sBliCjtSe@=H{1#6*|x6!8a17<>smly!bCr*gS$?+UTeeY za3jmblIFh+ydk45S5b-yk9FiftKop%*=lC+9qcgYmVKe<*f{>_MQLZlM^2oqpGvG= z?$phU{-YkqI&tJE&NhGfIEa&)hh@YtxM$$&D2~E!#az<$(a$wV%nx_gb(eYMsEJq4 z*!gcs1W2qpYAEmmnLar$WWNxxA2hpCxj`QGshn&mODBj}-b`7`icEngEUC{*NkAaw z=Eh#Z2{p!)d_Us!Jj*LvX=jx$>0MkvXO5ElWQ~k4X%OJ77rNXQxXfuxWvW;9-+EZ9 zvT?k6Z&spfj9qkF+5w6Xvaci$DAx=MImX6t^hN>)@E%?w^_2G4%r)yE)3y3leJpoB z;@>L>gQ{UAM|<7%^Su1h`--CrK2+3I(uYBVH&b=V8>-5&xJFSNLS6g)>FodZGt;>@ z!$}d=vI!hG6%@b;?64Nzs`OyIvB~TpnV^T#k|f)IbK#`o4mEd&&lO)IShkfH!=&`g z7~FWVF$znmD-76;(S*ZEa%7cf_YI7Xy#8_XOqe*0n@`&BPV=pPN`7&DY#4vk{FRd; zdcW%`PQ{xI|C0OB|J}7}FM9o}y?RUPliF9ZM$jznJbw@ItFzI zON?Mf8^uW#Q^zM4mhfiM_0fM{VI)mvI@BJ)x2nu2`RltuzC6x*q}571$w7xx6Xc?NQv zlW`j;pazn&Qa5riUN9-?AtMab0EQzuYke@2|5}oAthrj+hDQ8O(!$c(!L2#V?Sr>A zG-$)Qy_l{?UoOVAF^g=I%k3$q?SovK=h_b}n2Q6aj9KE^)P7e_v@-gs!Za26OfrLk z=FD3$$br?ppD7#ux?vbXpw!?KfdL`t7g=88Jdr=^E%<`wyr^SZ;g;a+I`0$shXMo- z85O#G5-fqa2&ERi7uSXhzm+z(esJr)?e@X_WEQTDDdc8W_u&^|cu3ntseYB0-Zjy| z!ND`T(U^Hwukls$r;@Ct_U1M=r$ChX(X_A=?Hp^>nT-Ju9A0+6*xHI*@ywYs?=(2( z4vVabab*I58v_X%i(*|+Cnk?JQs zj4?V~pLmI25R&{T)}}Z@icugZUg4}foOC5+@ZX*Es^dz=NmV5PeK|<%o1hZ0)^m$t zvL))`$^9aw3gdvo>%jaWiqFVzMMg#qt6^5S~t%CAjW*zpfQVQ`G^(j1l=zR~G|^a^dW!L4^xm-Tv6>+Q`Jw zcC|5OXOPt4f*MF=k@d39U@S-Z}(V_@#vHW*Tq)T9o{ zYm7)_NPkSnNVOp1OJ+7U3)RNo-+xF!AzT!Y`RxBeC$d!R|9ry#;fEg{2&KNt=5VQ? zMb51%y#d;;YyV2mOV|TYG5{5hcUn0w%@yy1m<{k?h$063ILjt&=Qc(pb5RstT6X~Y zr&V_V>=cUQ}G0#fR!@B9Mar z@ByZJ!IvS>DD{;M4XB0Y8&=`>3Bbj=k*9!b05##cGv)z|fYA&j$kJHNM4$_GWGf8(IfFlf zJRy3V=ixY4?P}wWA8^@?yyNW>XEwLPPdtDOsdS$Jbtslf--#)KJ<5=R1StFjDq7h~ z&5HL~BQP^HiE~n-w_&ZlPBoGOk4e-xGkA}D7TE#++iQ0e`MVeXFLnUk1|E6nCGqY? zaEt{5H^DbL2`kq+>Qdf)PYw(keE5>S-1Z>Y5?^g{^*))~!*&`-J(f5b$@E)5I_56| zRhqY0f2*Kt=kR>1QPo)J>OM+Vdl)Sm1zM7{0Yi4%A>Ber%DlA12zOb@?Oih-Zmvu3 z0W@V|M+R8DGwpokkyf<&D{UeAm`N{spzX>=O6>vCvreb!lU}TwP0{Ap2YHDgeSGoe9=+5NJ1=D&w5lm3a00}s>XzGlFI8xb& zo4HThs+cAOtg$n#ds6!4-v$GVTW}rlgBUiYu3IH~XTbytHYLSqiF+K%dRBMfF~qy! z0oqE8V4YwSaKtN#`lYktFP!saDl6v_!u1>)~VMRqa zs2N?MiifWPN($}?m_guh4tp4vK@L2R68v=`%#i|5L`zT4GLhJtnq^b&y~Q!^HAe@2 z`gNbpd}UXPu&V_x^{akc)BE=cV7Lbi(t0%K1vdy$!`T^Ba*;cLZ}od4v?7aB>Dojy>fBHrl#u zFN2R~TH>S4i$V@RYIepOdwcK3@^@|M#mM}@j%6KyasV=90MS3Am-Kz{5;ZU|;0!gH z^87Q6yin9I{$t`{NQKPd_-|wbaPZb8dTpZ}AgYavy2D2PitRMmjat5|g#b-Pk2Q1a zXV5*0kk5QJI_nS9h@7We&Q@=9iNV+u_`~BXxffbnQxjF?u{sqKaBvw=$x~lrdXLKd z>D8l^)u)|SabnZ&H6ma+|3*<5Vu3=!A51cV4Z@qG3~n2#8jY4akZRqXisboFTpSE4P38G1Twe}hNQgW* z2afoM`HKiUnhc#bJd6Ww$m>SL5n-BDx&NUk7|cuBM<+fN0SOR&U@RO2x&%v^fpk9w zn9Bf@GM83YGmQ!|`xYQ3Ai7MI`Q|WtMV$UJI4U5!H@c--^YqK0a$X_Ie+$+Ykw}6& zXNq7t09mbDo(>VGX8{cuQ@PLgXZRgW%@- zjD)ehf+M8}_<-w=R=S<3Fou$a582p&j_(uPA_?}dH?luh(K2pId9s+d!2?8_{#^uxjc7YrJy(bQn7{#8n zPBY)BnBfCFS9M^{Krz10ObPNod{`?W; z>bN199jInfdT&c5WoU7X%fYA+m(qp2B}G6?1}>#|3C#Q9a%Cw0KP(~7@BeZG<#kRu2w zN9&h4WN77F@zJV-vg84jvw4tr2ICojAkR{$^C&x;sLvJRuNiEKqEoOfQU z$I%(tarUL1{kGb>nwlV3_Q+%0i&dloM1nz6owWi-qhR2f>RV{*xcmMafBJ}>kVCv)zMO=d*(>#~(Ch~W*Ig}t-;uN*8fHH&HsU0I+&UtPuHDFvj;9r=g|?VGMw4W)GWJBmUDz z3shjEFilnQdh}wYVk6y<^_*@{7rfIqW`5N;iAYRylIeLo?J&PMX}U3S<;)S=G|CgA1e<>hI6OIFBP z!JsDC7DKU`(8B<_xq#f6_uni+cZJb}Ls{H1UeSdiUGt~4(xHu}y%pCYFw7>Oxl4+C z1>@RGz+pkhMt1hp{5;z!&Staqr0(TPBqYTKeypucTPk}-g$rmgrIW>@ZMOOCoR_2Q zeF<-gPrS+x*G+f>vuxU&6Wc6e{kXETnbNz>0U4aC1n+c5bF0D!UsF>h`YQDJ=u#^8 zDXWf#nj)@=FR9*{7LwaZr!a8BRoiH1Jek1112%iCpVN~3-gTvAeQyMwO-ElpILii* z=HSo}bUr|0EcM3+)Og|Uz>o=~m*i3<#=EPAPNhm*a35I~1m1unUetL!Zq*B3XumB5 z?3vJMVFa283kOaMLl;VSZqo&Dd5~&?+8?k2+5H@le<8t8wWN4XdILi5R$Ut=z#l}AH;`WB}Ckz2I0p|v4m3zMQu#*6b zf*%SsW!4l2_nu_U=o;!^R*G_;l2Rq>6<~H;4x-jb^qT8I%nqrgO#>SOQ zQm~!k0~NSYx#!6b|I0o)7Xo|#nO~W||LKg9*N&es zEyVYkjXjGdQbyI`qTr&@i}+#ZkDP=ba)r3`hq303J#Hp@ZsyAI7{8H0#`-0 zPs*pz0nnD>ST>?k`Bf5vx#B5H_|-U8H7A&C*OABrua$y;fB-7@QS#GV$8DRTPkmm1 zW-?0smvEIHR~yCi8yQaxHrw{z!B&PW4CZddE~}qZ`KLgHQl`d8?M9SMGHhN*xD;PZ z?JqU&h!$)?bOu~Sq^XI3Eo9g;3@bwtH)#2QG?Il1Qs{%uiG#C9KGUn0Oj0bQ;vZp) z>qR#N-#;$=+gsJ>xNRewcA91GHVHlsfWkh3Zp(&ffa0efG7j-vxowu-e^xhPdayM0 zxx8oE&ZoEs)S;|t`tEdop^}4-VbsbgvDb6R(CE?d|SNxcC>_-jEK(?JDl_yh!e8B5NnKH0^kV~27ye} z$_bftB9umR=JngcL~<$7xOi@E-Kk&uk|<^$OghEu+0U0miX6r1(+55N_?c3(2!+k8 zJ`GT#FRNW;jThqkGUp;P<5KbZEv}(5VvzZ`?d#9Lg$*oT8QGe-rTa{Wi!!d?+Tq$O z?dv{t>^Y7GwzXkuiU|&Np{jp}jC54(26DYXUHRq|i} zn5CDwcVQz!yhL(Z2*k~1WZ+X1EK_YIMLQoSiqHeRf;>8|tF1`Jy21cFyW*9krJ@5+ zYh|62(|y*EA}pZhdEF`KvsZS(V&`FjmqX>Q(blf;aR290?B9qO(MC-o^M(|>87?<|AWsP;sfhS8`#hG z@hxsy47IK7TZ$Lu_H2lw6lgZ9=Vw?`wmugzR!GfxbxY7h#agj-4_Do!dd!s)?~yrs zly~2)E5WiHfQ9;V3#rA9>h*RPLCDWwATpB50xE_Z-QAszaR%4`R%NkC#KXiRS<%^4 zy8PNsYegzmV%uWq#ld)FdkeGfa1D^7jl8kzv_*XfAOwKi@LRQXmZ%NzlI=dTPi)4& zR=lwA%7Cj|4opn6FpDvCw77?w9?TcArt7<769hugxseg*E18Z~=Z4f})i=!GXZi;)U?^W}j54{BBS!PeYr+5qaqTU6xOLY83AixrE zOVAYc)wU$o${WCZW&XyfhfJrS3%2ZZV~_P_Fyqx7v8sH~*^Ij=#Usi+B6tcct`l@=Pxe_BFS71`~@bY#z=~YLq_L?J?Zwa(= z-&S{k1TQNkxE9&Mh3;EKnp`V+JIZY2flY~?cs%V zmHC%bI*;ZriZMnP^jJT#Dh>yIX(Y)9N$(o~#^2m+DDdCn1f&f~68!^LSxrr-D4eio zaaqd0#jm7He2KQccv5Wv@KM3$n=tfy7_t)gDnF)|kPraT@TDMuvj>6yz*hqsnQ=!r z=a?MbVqx->%Kro-{~%Z`Go^;sTnsRaa6VF~UpkiVr)$M4C9L}>6#b~8tc(UNSH~y7 zF_P(zr-fO&;(rhFK%*(p#_D?*ht17xB(ut2oC3jwLw^Qf0->iC*_`o-OYgX1`~dH9 zG&3v`s&0z^7UhF_Q{UOjv6b-kcP>lmK#TcQXJ@xP{Nklq`#WL-8<=>A)j*NnA-__w zyNDKrEJpF|G8j72?h0d45fV>N?-M)?2Mh`U56Q*f-1S^R z7-xRv#bjm;3Iy z^lpZ8vvd@}Pw#NVLva9nL$sK#5j3QNbKTzAaR#vmBtM0O5=a0!gd$LR2}wER^AKU- z%1FWqbg$dkjM?3B1G^GEgrRtIH^@@AjmyTtzM>qqKImGtLFNpRv}lMcqS>rSu4U(N z#vAAn#t0?^H4;(v*t8L^A%&EIMI?zV8v(;XScm9a18!Sfw(Wgq1L+m4+>H`Fxe`4;QxR3sRQWtDVC_G_62O@D zhY%iS9C}Q6r89e^3kGht56sAPtz=M*EEzbrI+KP@hMPMI(*k<}Yys?S*abw7ZyG=a z3~mldNzT$1U#ZyN-$%0Y^{oNpX`o?|e!M`)tO+H5dSOW0J#EWo#_`}Z|sR9jEO;w_w~KvA;!Z_p@|;|bp{-4VRiKr7_p2j z{m;%6SP4tr9X!_Cr_O|63#i=QX6-QVc7ACw@f$!dkQfLw;fMzhY$UuW8LyOa_dW2z zh+#vv2rNr*1LOOnSWQaEdw?#3I$D+uQ%dJ=iJgatCApO74!FTXB3!qS+l=k2+}fvg z{1F(7kmNaWZwhc4kSanQ6tvf2ZK3!HCeh|U4-yOVnON|4Hg7%S?45J#nkEYf`do+u z*8{%^#LgXZJYbRV7~AXZMp_^M0U!X2I303>@4K{Mg^e^8;1`N(l(} z(3OgC#IU>Jf59pdUK2P;+Y-H^f>3VmA!f)Iz&9aaFgF*T5y|60nnN+<6KpQXE$&8_ zL%B<(FZK+UVl6vo#6wv0#>SgaKtQBo21iDao@cOS*x8^3p2B{#O5#-kgIE>XlJJx@Q*@Ff};vpb@lt?pgO- z`d(EG$eO@^L)JIP1*MkN*O4k+9MF=AbZi0{@@i2OF1!9#>X3ct`$u4A!O1}BgqC#y zO#_-6Yiqn-k{3WdMfqHq--KE;yKejj0+w=mVYdO11x^m)3VZ-y|A6QVIa_XiJ{SS` zU8F|h;K0(FlKW?9WF**>8a7NbWTkLer)<6R8N4dhw{aRb{#FR2Dp*Fw$6FGO{ZBy@ z*-`Mi?7bcOvHE+Tz}X4|VyFZH`11Tca|$R?SX88}Y*9S)diX5@Jc-+9e^&@4&LXcG zhaDIRU_Ju&%L2}HZ>#}1i;zmE#E^2^O~e;zL!l8#gfERrkPMUu93#jT*JL=cX~z#C8o|3L-sFp}tsF$4LZMDm)I}kX3KA3&f=X1PayxKp z5MFB3iiYg?C~wny_;#m~M9E(kVd!6UgXJ{^S^(|^>;@@HOjdG(g3IHQlIw67W4Wo6 zT+wK;?G$cu79xkF!-WJ+gx_^=->*#{HK_L9vi)u3H!kD|89TL{`cZ(-&h|))n;Vwz z*}3*hk7>u*BbcuKGSf{+t&~PdedLkZ=#>&-i@=wEmKAb-ppZ`gF0=Z%D@INGexEPZ zJvLFjqOZs-rh1^eNI>mumQ2HkCL)j--mQq%o~Xeb0oKt*b^p^OB_aDiD?cVqsdg1>XfgGsVUH;60vqSgsqu zWb}+Xgp%n%w$Q<@5f%|4i^2e71yj+R=sZzoHan1MPOS@rgY`TbBaLOg1SeylY2~Tq zg%}2@79b6p?hZ;b2Ey0>%LIVPO0Wd)`$~fYmO6ayG%hwq@6ffnMcu#77=2cgJcQH9 zfzrI> zd0(=I?*(QOV?A}9IWr{#N|vx)j^WC(VJlnSW=tIbfq`3#Xl6o^ZB5PQgy$PF!&ToS zTc-&_ZomiL3Zx!D>A@N`EG)3&2M3jl?5$1Sg!p7)Z?CfXZdc-(LcpUFhUG=4m6IV= zk2N`rqo0bDI2RsPHTqsdN#HS58md1quNPTHLHtSY#z8rZRfa%}opfTm@ujynmii_+ zA+G<<`Ir9sKt57NhM$obDFtwhb)X}o__hz$1h92j>om$=yxXN>G{p5PJm;AX18#x= zw`ZMJ2vmW3F_g$##vDN!Nby{38#C~Q0XtRCH%H)Az!zYWV>_+n6nX^ChRfdIYS_}^ zlw~3#KOJ(0V!?usU7qIfrL{l=pqgvO{iXKsS1+>m#*Hrfc~)NuAIHOF*??yvrHV|j z40r8b{JE0%3UwrutunABRGR4-<7!9+v>>o)FjAf>y})SoTtW7RtIF&7=?%&Jt!nkR z;j-9JI|-Rsr7{nzUTNFdGY~J(Uii7Q+<7jt87V5_Vq*cK0WaNC;>VX17V7c0lw1Y} zzvgE57?%wfQ>jja@XEIRi!64UVUg&|E};X)t)=$sUVnUIf4+RS*0Y}AvFo{f3~#VNC+*FwkNM$XJ@K5d;YeBrgaPLp`pt5Odyxa;;Rra{cnOWn)W^Xv;C z7pw)&WrkI+>aY5Id(dK?%)+dA&PS!D)hlzf%VRXHdk(mK_)NL>=Io+K$9{DOWEF9E zx>m$1ZA$&=NQARPN9%Z@m$g65ZN4s)Q-MsjAn~yDxR{`ASZxNhZKy;DP#+ z)>4L-plt}bv3u3o^zO$dykRE1gmUUoYxk`^zM7q*m4g^DWLE+-a$J|V?zs&SD7=GoV0Je2F+zQaJ_bI3UM3;v9QqsMs%UCLjp$(m zBj71ua>2`W&ox@`HEhgv7gkk84%y+4l#-nefr>xS!HgYz5Hpybg%M^$i4KwE5EE-e zi{hc!BA960-rQw}`;*P=@$lwB(BSXc+fYMlGP@?5ss3fo75o=eo*=)n;5((M30(_K z*UCoh;n~58;jiH}faPa*0!V|_MTqv$MJ6mNdZWUCa@8@j2ec8UN&t8vP6(J-gh6u> zCNH=~N(dd33bBt)GW95+DvlVufm7h6egt&71)l;-93d|D>gEw_fmWC%0V{R-Z?y&J zV8FwO=*!*r%txaqS~hSeAgWe35d-CRKo|%qJKK?n^doe2b@8Tj{;13+^Z`g4u-nK0 z{f>+sMY~=+M%DGu$|nSA8vIssvmCU7K@^4*3);tkLc2|S6Sx>)Mn?vLP@JdNrWkMD{}g#3o5esC-bE=fSST z^srGnWvmHhA;8l^Ll@44<3e^1`x*SOoghN{K<@+4 z13k7Sys4_qcE8{`0HT9C1=~Bxab!(c!3z-~ZIV3{@3J`(I9sQkArXUOX`%8yFn|;O z`&R)!K*WW0hY}*dD9{axP+)$DEYs>vB&jxZN)!x0w+)!d`mcV3Wdib~0sboes^U3c zNd~mxEv9F%g#p6@ENd_!{R_*04uG%^m4N7ZgJogjzbP2>KEi+8$RGtfdpB$}u;-L( zLj(U8n(?6F;4JJ;wCL3qP2GeL9WH?S&{xX%a0B!~0lTQGsZ9zK!>XvNs{Yv7hkFH+ z26#2NZvZ`4m6hJ6HXf4cRAUv!b(erSht>*6T;b7<_9u>S#4`KT>5QU!T>H4DF+rb|vRuOF`5QPZ= ztOD-{QXG)B`O%+)wCoNJ4}XFt7;SJT^Oez%0P)oBVpmmFG09#Gg=C$K`0)gXLiz+r z{-P*k<$!NNgbFg&rs=Fcc6e0yz#ssi=N3d!$YF0F20sA`Ex!QmQqW-4oCefW6hK~t zaz`e2a8ceAr>|Q(GWc%S>4q>R&=>%^gj0}534!Y38ZvMs-ETYT-DfGEZ6agebv&d| z2RfW}60STHLAKK&IbuPWG6DJ+=mmn$I7$@s01PcpYwe+i%cr!_sw5g3TrCeR|-w*ase8h!f&Op~+T$>SVf44{Z%#}o=jHqZ z|KpGy?GsoFuMKuGAaTIs&{E|gi4R`h^W?aX;XUx9d0ICiM+fo^q66$KXz+$a15sY4 ziGpYXn*bVqko}MJRTi$gOQuJ*TQiaZi+}EHsdy}N_)i@p;bRG}egoZvX8);;)|oLz zU_OzA5NH8rd0#KOS_-*_o}Ooe3@e=&$%+1#5R`A8ocuzoz;=M%1#thsGQcYdlVw5} z>hIqZ=H=m#u-%9}OI*X@{?2-0-2omT1xN98D%l#p)*>$BcLwPsy@_t`j`C{gUmH7a z&t4sKfPDtCT6ITTJibSJb4a^XOH1gxmx#RrNze@U@b1;|uuO6W+`>4)iLr8m{2t&B zunxEnNXY?cJmTs=FdV9{U;1Eo-EU)LiX1**u>2cIu^kK+bo!9UM^G;gZqJ4XDt9{ z9dLiN=1&28kzjdfVG^Ki^i+}o1~5$-o&UIjbqp+0o5k-aD@)0AHH}HYqAYRY)Ky!z zt0m^fufZk+ZVw1$?Yq1IQ4h8J#XEROS0*>~Hftv%CQL zZF>$^hZ(vLn){$R93pd0KY&bm7ztxP0`Ymsj`EqpjFQxxy{D$7ZUXQVTpidb0I%R- z)H}HoJAh?FZi8m|8S^Q?{^X~zP|#h#5g$RgFzG}cB>jVxvlZNS5f^}3FlZD+uD?(g zfDCv5R#w(2VW<@VknUahC~O4*qT{4(->?DT5a1Pvmuh71 zzM?Q*-v}wA&bE;R+&zDQwp25*?ij z&XKCA14U6paaBn1L#GQ(43(x3$`U2x#iD~1q22EmX7*uCKQv9-^xxidp65LGIp^MT zr0=~tj$MR2BUDxzFnlmm;U*G>@XggMCi%CHSx)-=x0zx#HZPB^obA^@7iV>FPGE4^ zS+lXYfvvoBi<&?pM|KRnFh;qw){o<)!g`MU&B_nA+=PNg|5S`j2JKb<6`cN}h=L1H z7B)ZJvAE6<;^U;X&%B^=Z*Q;Fc~74opWIg5mL&8!{tP5g&S9?A5B5D0Zv4nfokdAVhEn84Uz!63QT5=bx=`8Ek4l{$E)1s}2YU zvLlAnic0Q~K8v*7Dv$niGHRqZ#x7tlGz+<}i3oPOeq$EU8bc9An z&P)W#_=(A!1e30!sZ#&y~1?Kcsc7TQq+jNJE?x zFgE0Tk8Y3PS?eb(o!NPN)bQO2LRBE3Uj?MI}-rSzutT`c8XVaTr$>)iEM~ z_R@4m|J(GdE{QJ4+{l03N!^Da!3XL%5$s(%2$4@%tt literal 0 HcmV?d00001 diff --git a/perception/multi_object_tracker/include/multi_object_tracker/data_association/data_association.hpp b/perception/multi_object_tracker/include/multi_object_tracker/data_association/data_association.hpp new file mode 100644 index 0000000000000..23feca474fe4f --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/data_association/data_association.hpp @@ -0,0 +1,62 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_ +#define MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_ + +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include "multi_object_tracker/data_association/solver/gnn_solver.hpp" +#include "multi_object_tracker/tracker/tracker.hpp" + +#include +#include + +#include + +class DataAssociation +{ +private: + Eigen::MatrixXi can_assign_matrix_; + Eigen::MatrixXd max_dist_matrix_; + Eigen::MatrixXd max_area_matrix_; + Eigen::MatrixXd min_area_matrix_; + Eigen::MatrixXd max_rad_matrix_; + const double score_threshold_; + std::unique_ptr gnn_solver_ptr_; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + DataAssociation( + std::vector can_assign_vector, std::vector max_dist_vector, + std::vector max_area_vector, std::vector min_area_vector, + std::vector max_rad_vector); + void assign( + const Eigen::MatrixXd & src, std::unordered_map & direct_assignment, + std::unordered_map & reverse_assignment); + Eigen::MatrixXd calcScoreMatrix( + const autoware_auto_perception_msgs::msg::DetectedObjects & measurements, + const std::list> & trackers); + virtual ~DataAssociation() {} +}; + +#endif // MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver.hpp b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver.hpp new file mode 100644 index 0000000000000..631fd73f8583d --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver.hpp @@ -0,0 +1,22 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__GNN_SOLVER_HPP_ +#define MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__GNN_SOLVER_HPP_ + +#include "multi_object_tracker/data_association/solver/gnn_solver_interface.hpp" +#include "multi_object_tracker/data_association/solver/mu_successive_shortest_path.hpp" +#include "multi_object_tracker/data_association/solver/successive_shortest_path.hpp" + +#endif // MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__GNN_SOLVER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver_interface.hpp b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver_interface.hpp new file mode 100644 index 0000000000000..1fb508bcf12b2 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/gnn_solver_interface.hpp @@ -0,0 +1,35 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__GNN_SOLVER_INTERFACE_HPP_ +#define MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__GNN_SOLVER_INTERFACE_HPP_ + +#include +#include + +namespace gnn_solver +{ +class GnnSolverInterface +{ +public: + GnnSolverInterface() = default; + virtual ~GnnSolverInterface() = default; + + virtual void maximizeLinearAssignment( + const std::vector> & cost, std::unordered_map * direct_assignment, + std::unordered_map * reverse_assignment) = 0; +}; +} // namespace gnn_solver + +#endif // MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__GNN_SOLVER_INTERFACE_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/mu_successive_shortest_path.hpp b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/mu_successive_shortest_path.hpp new file mode 100644 index 0000000000000..a4d9d727e6cc5 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/mu_successive_shortest_path.hpp @@ -0,0 +1,37 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__MU_SUCCESSIVE_SHORTEST_PATH_HPP_ +#define MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__MU_SUCCESSIVE_SHORTEST_PATH_HPP_ + +#include "multi_object_tracker/data_association/solver/gnn_solver_interface.hpp" + +#include +#include + +namespace gnn_solver +{ +class MuSSP : public GnnSolverInterface +{ +public: + MuSSP() = default; + ~MuSSP() = default; + + void maximizeLinearAssignment( + const std::vector> & cost, std::unordered_map * direct_assignment, + std::unordered_map * reverse_assignment) override; +}; +} // namespace gnn_solver + +#endif // MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__MU_SUCCESSIVE_SHORTEST_PATH_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/successive_shortest_path.hpp b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/successive_shortest_path.hpp new file mode 100644 index 0000000000000..1c4b15cd68b59 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/data_association/solver/successive_shortest_path.hpp @@ -0,0 +1,37 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__SUCCESSIVE_SHORTEST_PATH_HPP_ +#define MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__SUCCESSIVE_SHORTEST_PATH_HPP_ + +#include "multi_object_tracker/data_association/solver/gnn_solver_interface.hpp" + +#include +#include + +namespace gnn_solver +{ +class SSP : public GnnSolverInterface +{ +public: + SSP() = default; + ~SSP() = default; + + void maximizeLinearAssignment( + const std::vector> & cost, std::unordered_map * direct_assignment, + std::unordered_map * reverse_assignment) override; +}; +} // namespace gnn_solver + +#endif // MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__SOLVER__SUCCESSIVE_SHORTEST_PATH_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp new file mode 100644 index 0000000000000..d79180e4b2dd5 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -0,0 +1,79 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +/// + +#ifndef MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ +#define MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ + +#include "multi_object_tracker/data_association/data_association.hpp" +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +class MultiObjectTracker : public rclcpp::Node +{ +public: + explicit MultiObjectTracker(const rclcpp::NodeOptions & node_options); + +private: + rclcpp::Publisher::SharedPtr + tracked_objects_pub_; + rclcpp::Subscription::SharedPtr + detected_object_sub_; + rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + void onMeasurement( + const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg); + void onTimer(); + + std::string world_frame_id_; // tracking frame + std::list> list_tracker_; + std::unique_ptr data_association_; + + void checkTrackerLifeCycle( + std::list> & list_tracker, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform); + void sanitizeTracker( + std::list> & list_tracker, const rclcpp::Time & time); + std::shared_ptr createNewTracker( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) const; + + void publish(const rclcpp::Time & time) const; + inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; +}; + +#endif // MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp new file mode 100644 index 0000000000000..30e23c096ce65 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp @@ -0,0 +1,92 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_ + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +class BicycleTracker : public Tracker +{ +private: + autoware_auto_perception_msgs::msg::DetectedObject object_; + rclcpp::Logger logger_; + +private: + KalmanFilter ekf_; + rclcpp::Time last_update_time_; + enum IDX { + X = 0, + Y = 1, + YAW = 2, + VX = 3, + WZ = 4, + }; + struct EkfParams + { + char dim_x = 5; + float q_cov_x; + float q_cov_y; + float q_cov_yaw; + float q_cov_wz; + float q_cov_vx; + float p0_cov_vx; + float p0_cov_wz; + // if use_measurement_covariance_ is false, use following params + bool use_measurement_covariance; + float r_cov_x; + float r_cov_y; + float r_cov_yaw; + float p0_cov_x; + float p0_cov_y; + float p0_cov_yaw; + } ekf_params_; + + double max_vx_; + double max_wz_; + float z_; + +private: + struct BoundingBox + { + double width; + double length; + double height; + }; + BoundingBox bounding_box_; + +public: + BicycleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool predict(const double dt, KalmanFilter & ekf) const; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~BicycleTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp new file mode 100644 index 0000000000000..991d9940a0f1e --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp @@ -0,0 +1,91 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_ + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +class BigVehicleTracker : public Tracker +{ +private: + autoware_auto_perception_msgs::msg::DetectedObject object_; + rclcpp::Logger logger_; + +private: + KalmanFilter ekf_; + rclcpp::Time last_update_time_; + enum IDX { + X = 0, + Y = 1, + YAW = 2, + VX = 3, + WZ = 4, + }; + struct EkfParams + { + char dim_x = 5; + float q_cov_x; + float q_cov_y; + float q_cov_yaw; + float q_cov_wz; + float q_cov_vx; + float p0_cov_vx; + float p0_cov_wz; + // if use_measurement_covariance_ is false, use following params + bool use_measurement_covariance; + float r_cov_x; + float r_cov_y; + float r_cov_yaw; + float p0_cov_x; + float p0_cov_y; + float p0_cov_yaw; + } ekf_params_; + double max_vx_; + double max_wz_; + float z_; + +private: + struct BoundingBox + { + double width; + double length; + double height; + }; + BoundingBox bounding_box_; + +public: + BigVehicleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool predict(const double dt, KalmanFilter & ekf) const; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~BigVehicleTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp new file mode 100644 index 0000000000000..144b1b6c9b8b4 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp @@ -0,0 +1,49 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_ + +#include "multi_object_tracker/tracker/model/big_vehicle_tracker.hpp" +#include "multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp" +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include +#include + +class MultipleVehicleTracker : public Tracker +{ +private: + NormalVehicleTracker normal_vehicle_tracker_; + BigVehicleTracker big_vehicle_tracker_; + +public: + MultipleVehicleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~MultipleVehicleTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp new file mode 100644 index 0000000000000..bdaef7309c916 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp @@ -0,0 +1,92 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_ + +#include "tracker_base.hpp" + +#include + +class NormalVehicleTracker : public Tracker +{ +private: + autoware_auto_perception_msgs::msg::DetectedObject object_; + rclcpp::Logger logger_; + +private: + KalmanFilter ekf_; + rclcpp::Time last_update_time_; + enum IDX { + X = 0, + Y = 1, + YAW = 2, + VX = 3, + WZ = 4, + }; + struct EkfParams + { + char dim_x = 5; + float q_cov_x; + float q_cov_y; + float q_cov_yaw; + float q_cov_wz; + float q_cov_vx; + float p0_cov_vx; + float p0_cov_wz; + // if use_measurement_covariance_ is false, use following params + bool use_measurement_covariance; + float r_cov_x; + float r_cov_y; + float r_cov_yaw; + float p0_cov_x; + float p0_cov_y; + float p0_cov_yaw; + } ekf_params_; + + double max_vx_; + double max_wz_; + float z_; + +private: + struct BoundingBox + { + double width; + double length; + double height; + }; + BoundingBox bounding_box_; + +public: + NormalVehicleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool predict(const double dt, KalmanFilter & ekf) const; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~NormalVehicleTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp new file mode 100644 index 0000000000000..ca1e5b519d708 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp @@ -0,0 +1,48 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_ + +#include "multi_object_tracker/tracker/model/bicycle_tracker.hpp" +#include "multi_object_tracker/tracker/model/pedestrian_tracker.hpp" +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +class PedestrianAndBicycleTracker : public Tracker +{ +private: + PedestrianTracker pedestrian_tracker_; + BicycleTracker bicycle_tracker_; + +public: + PedestrianAndBicycleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~PedestrianAndBicycleTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp new file mode 100644 index 0000000000000..a8f1923bb68cb --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp @@ -0,0 +1,98 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_ + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +class PedestrianTracker : public Tracker +{ +private: + autoware_auto_perception_msgs::msg::DetectedObject object_; + rclcpp::Logger logger_; + +private: + KalmanFilter ekf_; + rclcpp::Time last_update_time_; + enum IDX { + X = 0, + Y = 1, + YAW = 2, + VX = 3, + WZ = 4, + }; + struct EkfParams + { + char dim_x = 5; + float q_cov_x; + float q_cov_y; + float q_cov_yaw; + float q_cov_wz; + float q_cov_vx; + float p0_cov_vx; + float p0_cov_wz; + // if use_measurement_covariance_ is false, use following params + bool use_measurement_covariance; + float r_cov_x; + float r_cov_y; + float r_cov_yaw; + float p0_cov_x; + float p0_cov_y; + float p0_cov_yaw; + } ekf_params_; + + double max_vx_; + double max_wz_; + float z_; + +private: + struct BoundingBox + { + double width; + double length; + double height; + }; + struct Cylinder + { + double width; + double height; + }; + BoundingBox bounding_box_; + Cylinder cylinder_; + +public: + PedestrianTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool predict(const double dt, KalmanFilter & ekf) const; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~PedestrianTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp new file mode 100644 index 0000000000000..ed18f5b5ff777 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp @@ -0,0 +1,93 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__TRACKER_BASE_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__TRACKER_BASE_HPP_ + +#define EIGEN_MPL2_ONLY +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include + +#include "autoware_auto_perception_msgs/msg/detected_object.hpp" +#include "autoware_auto_perception_msgs/msg/tracked_object.hpp" +#include "geometry_msgs/msg/point.hpp" +#include "unique_identifier_msgs/msg/uuid.hpp" + +#include + +class Tracker +{ +protected: + unique_identifier_msgs::msg::UUID getUUID() const { return uuid_; } + void setClassification( + const std::vector & classification) + { + classification_ = classification; + } + +private: + unique_identifier_msgs::msg::UUID uuid_; + std::vector classification_; + int no_measurement_count_; + int total_no_measurement_count_; + int total_measurement_count_; + rclcpp::Time last_update_with_measurement_time_; + +public: + Tracker( + const rclcpp::Time & time, + const std::vector & classification); + virtual ~Tracker() {} + bool updateWithMeasurement( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & measurement_time); + bool updateWithoutMeasurement(); + std::vector getClassification() const + { + return classification_; + } + std::uint8_t getHighestProbLabel() const { return utils::getHighestProbLabel(classification_); } + int getNoMeasurementCount() const { return no_measurement_count_; } + int getTotalNoMeasurementCount() const { return total_no_measurement_count_; } + int getTotalMeasurementCount() const { return total_measurement_count_; } + double getElapsedTimeFromLastUpdate(const rclcpp::Time & current_time) const + { + return (current_time - last_update_with_measurement_time_).seconds(); + } + virtual geometry_msgs::msg::PoseWithCovariance getPoseWithCovariance( + const rclcpp::Time & time) const; + + /* + * Pure virtual function + */ + +protected: + virtual bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) = 0; + +public: + virtual bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const = 0; + virtual bool predict(const rclcpp::Time & time) = 0; +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__TRACKER_BASE_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp new file mode 100644 index 0000000000000..6007e20e8de6b --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp @@ -0,0 +1,77 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__UNKNOWN_TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__UNKNOWN_TRACKER_HPP_ + +#include "tracker_base.hpp" + +#include + +class UnknownTracker : public Tracker +{ +private: + autoware_auto_perception_msgs::msg::DetectedObject object_; + rclcpp::Logger logger_; + +private: + KalmanFilter ekf_; + rclcpp::Time last_update_time_; + enum IDX { + X = 0, + Y = 1, + VX = 2, + VY = 3, + }; + struct EkfParams + { + char dim_x = 4; + float q_cov_x; + float q_cov_y; + float q_cov_vx; + float q_cov_vy; + float p0_cov_vx; + float p0_cov_vy; + // if use_measurement_covariance_ is false, use following params + bool use_measurement_covariance; + float r_cov_x; + float r_cov_y; + float p0_cov_x; + float p0_cov_y; + } ekf_params_; + float max_vx_, max_vy_; + float z_; + +public: + UnknownTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object); + + bool predict(const rclcpp::Time & time) override; + bool predict(const double dt, KalmanFilter & ekf) const; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) override; + bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~UnknownTracker() {} +}; + +#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__UNKNOWN_TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/tracker.hpp new file mode 100644 index 0000000000000..75560750f07b6 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/tracker.hpp @@ -0,0 +1,31 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ +#define MULTI_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ + +#include "model/bicycle_tracker.hpp" +#include "model/big_vehicle_tracker.hpp" +#include "model/multiple_vehicle_tracker.hpp" +#include "model/normal_vehicle_tracker.hpp" +#include "model/pedestrian_and_bicycle_tracker.hpp" +#include "model/pedestrian_tracker.hpp" +#include "model/tracker_base.hpp" +#include "model/unknown_tracker.hpp" + +#endif // MULTI_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp b/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp new file mode 100644 index 0000000000000..95f81275e3e97 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp @@ -0,0 +1,87 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#ifndef MULTI_OBJECT_TRACKER__UTILS__UTILS_HPP_ +#define MULTI_OBJECT_TRACKER__UTILS__UTILS_HPP_ + +#include + +#include +#include +#include +#include +#include + +#include +#include + +namespace utils +{ +double getPolygonArea(const geometry_msgs::msg::Polygon & footprint); +double getRectangleArea(const geometry_msgs::msg::Vector3 & dimensions); +double getCircleArea(const geometry_msgs::msg::Vector3 & dimensions); +double getArea(const autoware_auto_perception_msgs::msg::Shape & shape); +double get2dIoU( + const autoware_auto_perception_msgs::msg::TrackedObject & object1, + const autoware_auto_perception_msgs::msg::TrackedObject & object2); +std::uint8_t getHighestProbLabel( + const std::vector & classification); +autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject( + const autoware_auto_perception_msgs::msg::DetectedObject & detected_object); + +enum MSG_COV_IDX { + X_X = 0, + X_Y = 1, + X_Z = 2, + X_ROLL = 3, + X_PITCH = 4, + X_YAW = 5, + Y_X = 6, + Y_Y = 7, + Y_Z = 8, + Y_ROLL = 9, + Y_PITCH = 10, + Y_YAW = 11, + Z_X = 12, + Z_Y = 13, + Z_Z = 14, + Z_ROLL = 15, + Z_PITCH = 16, + Z_YAW = 17, + ROLL_X = 18, + ROLL_Y = 19, + ROLL_Z = 20, + ROLL_ROLL = 21, + ROLL_PITCH = 22, + ROLL_YAW = 23, + PITCH_X = 24, + PITCH_Y = 25, + PITCH_Z = 26, + PITCH_ROLL = 27, + PITCH_PITCH = 28, + PITCH_YAW = 29, + YAW_X = 30, + YAW_Y = 31, + YAW_Z = 32, + YAW_ROLL = 33, + YAW_PITCH = 34, + YAW_YAW = 35 +}; +} // namespace utils + +#endif // MULTI_OBJECT_TRACKER__UTILS__UTILS_HPP_ diff --git a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml new file mode 100644 index 0000000000000..1baeb42d9b1d5 --- /dev/null +++ b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/perception/multi_object_tracker/package.xml b/perception/multi_object_tracker/package.xml new file mode 100644 index 0000000000000..0b1214f625594 --- /dev/null +++ b/perception/multi_object_tracker/package.xml @@ -0,0 +1,32 @@ + + + multi_object_tracker + 1.0.0 + The ROS2 multi_object_tracker package + Yukihiro Saito + + Jilada Eccleston + Apache License 2.0 + + ament_cmake_auto + eigen3_cmake_module + + autoware_auto_perception_msgs + autoware_perception_msgs + autoware_utils + eigen + kalman_filter + mussp + rclcpp + rclcpp_components + tf2 + tf2_ros + unique_identifier_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/multi_object_tracker/src/data_association/data_association.cpp b/perception/multi_object_tracker/src/data_association/data_association.cpp new file mode 100644 index 0000000000000..3f3c523c73afa --- /dev/null +++ b/perception/multi_object_tracker/src/data_association/data_association.cpp @@ -0,0 +1,212 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "multi_object_tracker/data_association/data_association.hpp" + +#include "multi_object_tracker/data_association/solver/gnn_solver.hpp" +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include +#include +#include +#include + +namespace +{ +double getDistance( + const geometry_msgs::msg::Point & measurement, const geometry_msgs::msg::Point & tracker) +{ + const double diff_x = tracker.x - measurement.x; + const double diff_y = tracker.y - measurement.y; + // const double diff_z = tracker.z - measurement.z; + return std::sqrt(diff_x * diff_x + diff_y * diff_y); +} + +double getMahalanobisDistance( + const geometry_msgs::msg::Point & measurement, const geometry_msgs::msg::Point & tracker, + const Eigen::Matrix2d & covariance) +{ + Eigen::Vector2d measurement_point; + measurement_point << measurement.x, measurement.y; + Eigen::Vector2d tracker_point; + tracker_point << tracker.x, tracker.y; + Eigen::MatrixXd mahalanobis_squared = (measurement_point - tracker_point).transpose() * + covariance.inverse() * (measurement_point - tracker_point); + return std::sqrt(mahalanobis_squared(0)); +} + +Eigen::Matrix2d getXYCovariance(const geometry_msgs::msg::PoseWithCovariance & pose_covariance) +{ + Eigen::Matrix2d covariance; + covariance << pose_covariance.covariance[0], pose_covariance.covariance[1], + pose_covariance.covariance[6], pose_covariance.covariance[7]; + return covariance; +} + +double getFormedYawAngle( + const geometry_msgs::msg::Quaternion & measurement_quat, + const geometry_msgs::msg::Quaternion & tracker_quat, const bool distinguish_front_or_back = true) +{ + const double measurement_yaw = autoware_utils::normalizeRadian(tf2::getYaw(measurement_quat)); + const double tracker_yaw = autoware_utils::normalizeRadian(tf2::getYaw(tracker_quat)); + const double angle_range = distinguish_front_or_back ? M_PI : M_PI_2; + const double angle_step = distinguish_front_or_back ? 2.0 * M_PI : M_PI; + // Fixed measurement_yaw to be in the range of +-90 or 180 degrees of X_t(IDX::YAW) + double measurement_fixed_yaw = measurement_yaw; + while (angle_range <= tracker_yaw - measurement_fixed_yaw) { + measurement_fixed_yaw = measurement_fixed_yaw + angle_step; + } + while (angle_range <= measurement_fixed_yaw - tracker_yaw) { + measurement_fixed_yaw = measurement_fixed_yaw - angle_step; + } + return std::fabs(measurement_fixed_yaw - tracker_yaw); +} +} // namespace + +DataAssociation::DataAssociation( + std::vector can_assign_vector, std::vector max_dist_vector, + std::vector max_area_vector, std::vector min_area_vector, + std::vector max_rad_vector) +: score_threshold_(0.01) +{ + { + const int assign_label_num = static_cast(std::sqrt(can_assign_vector.size())); + Eigen::Map can_assign_matrix_tmp( + can_assign_vector.data(), assign_label_num, assign_label_num); + can_assign_matrix_ = can_assign_matrix_tmp.transpose(); + } + { + const int max_dist_label_num = static_cast(std::sqrt(max_dist_vector.size())); + Eigen::Map max_dist_matrix_tmp( + max_dist_vector.data(), max_dist_label_num, max_dist_label_num); + max_dist_matrix_ = max_dist_matrix_tmp.transpose(); + } + { + const int max_area_label_num = static_cast(std::sqrt(max_area_vector.size())); + Eigen::Map max_area_matrix_tmp( + max_area_vector.data(), max_area_label_num, max_area_label_num); + max_area_matrix_ = max_area_matrix_tmp.transpose(); + } + { + const int min_area_label_num = static_cast(std::sqrt(min_area_vector.size())); + Eigen::Map min_area_matrix_tmp( + min_area_vector.data(), min_area_label_num, min_area_label_num); + min_area_matrix_ = min_area_matrix_tmp.transpose(); + } + { + const int max_rad_label_num = static_cast(std::sqrt(max_rad_vector.size())); + Eigen::Map max_rad_matrix_tmp( + max_rad_vector.data(), max_rad_label_num, max_rad_label_num); + max_rad_matrix_ = max_rad_matrix_tmp.transpose(); + } + + gnn_solver_ptr_ = std::make_unique(); +} + +void DataAssociation::assign( + const Eigen::MatrixXd & src, std::unordered_map & direct_assignment, + std::unordered_map & reverse_assignment) +{ + std::vector> score(src.rows()); + for (int row = 0; row < src.rows(); ++row) { + score.at(row).resize(src.cols()); + for (int col = 0; col < src.cols(); ++col) { + score.at(row).at(col) = src(row, col); + } + } + // Solve + gnn_solver_ptr_->maximizeLinearAssignment(score, &direct_assignment, &reverse_assignment); + + for (auto itr = direct_assignment.begin(); itr != direct_assignment.end();) { + if (src(itr->first, itr->second) < score_threshold_) { + itr = direct_assignment.erase(itr); + continue; + } else { + ++itr; + } + } + for (auto itr = reverse_assignment.begin(); itr != reverse_assignment.end();) { + if (src(itr->second, itr->first) < score_threshold_) { + itr = reverse_assignment.erase(itr); + continue; + } else { + ++itr; + } + } +} + +Eigen::MatrixXd DataAssociation::calcScoreMatrix( + const autoware_auto_perception_msgs::msg::DetectedObjects & measurements, + const std::list> & trackers) +{ + Eigen::MatrixXd score_matrix = + Eigen::MatrixXd::Zero(trackers.size(), measurements.objects.size()); + size_t tracker_idx = 0; + for (auto tracker_itr = trackers.begin(); tracker_itr != trackers.end(); + ++tracker_itr, ++tracker_idx) { + const std::uint8_t tracker_label = (*tracker_itr)->getHighestProbLabel(); + + for (size_t measurement_idx = 0; measurement_idx < measurements.objects.size(); + ++measurement_idx) { + const autoware_auto_perception_msgs::msg::DetectedObject & measurement_object = + measurements.objects.at(measurement_idx); + const std::uint8_t measurement_label = + utils::getHighestProbLabel(measurement_object.classification); + + double score = 0.0; + const geometry_msgs::msg::PoseWithCovariance tracker_pose_covariance = + (*tracker_itr)->getPoseWithCovariance(measurements.header.stamp); + if (can_assign_matrix_(tracker_label, measurement_label)) { + const double max_dist = max_dist_matrix_(tracker_label, measurement_label); + const double max_area = max_area_matrix_(tracker_label, measurement_label); + const double min_area = min_area_matrix_(tracker_label, measurement_label); + const double max_rad = max_rad_matrix_(tracker_label, measurement_label); + const double dist = getDistance( + measurement_object.kinematics.pose_with_covariance.pose.position, + tracker_pose_covariance.pose.position); + const double area = utils::getArea(measurement_object.shape); + score = (max_dist - std::min(dist, max_dist)) / max_dist; + + // dist gate + if (max_dist < dist) { + score = 0.0; + // area gate + } else if (area < min_area || max_area < area) { + score = 0.0; + // angle gate + } else if (std::fabs(max_rad) < M_PI) { + const double angle = getFormedYawAngle( + measurement_object.kinematics.pose_with_covariance.pose.orientation, + tracker_pose_covariance.pose.orientation, false); + if (std::fabs(max_rad) < std::fabs(angle)) { + score = 0.0; + } + // mahalanobis dist gate + } else if (score < score_threshold_) { + double mahalanobis_dist = getMahalanobisDistance( + measurements.objects.at(measurement_idx).kinematics.pose_with_covariance.pose.position, + tracker_pose_covariance.pose.position, getXYCovariance(tracker_pose_covariance)); + + if (2.448 /*95%*/ <= mahalanobis_dist) { + score = 0.0; + } + } + } + score_matrix(tracker_idx, measurement_idx) = score; + } + } + + return score_matrix; +} diff --git a/perception/multi_object_tracker/src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp b/perception/multi_object_tracker/src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp new file mode 100644 index 0000000000000..18779a7fffbdf --- /dev/null +++ b/perception/multi_object_tracker/src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp @@ -0,0 +1,41 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "multi_object_tracker/data_association/solver/mu_successive_shortest_path.hpp" + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace gnn_solver +{ +void MuSSP::maximizeLinearAssignment( + const std::vector> & cost, std::unordered_map * direct_assignment, + std::unordered_map * reverse_assignment) +{ + // Terminate if the graph is empty + if (cost.size() == 0 || cost.at(0).size() == 0) { + return; + } + + // Solve DA by muSSP + solve_muSSP(cost, direct_assignment, reverse_assignment); +} +} // namespace gnn_solver diff --git a/perception/multi_object_tracker/src/data_association/successive_shortest_path/successive_shortest_path.cpp b/perception/multi_object_tracker/src/data_association/successive_shortest_path/successive_shortest_path.cpp new file mode 100644 index 0000000000000..0b52c09cb54b8 --- /dev/null +++ b/perception/multi_object_tracker/src/data_association/successive_shortest_path/successive_shortest_path.cpp @@ -0,0 +1,370 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "multi_object_tracker/data_association/solver/successive_shortest_path.hpp" + +#include +#include +#include +#include +#include +#include +#include + +namespace gnn_solver +{ +struct ResidualEdge +{ + // Destination node + const int dst; + int capacity; + const double cost; + int flow; + // Access to the reverse edge by adjacency_list.at(dst).at(reverse) + const int reverse; + + // ResidualEdge() + // : dst(0), capacity(0), cost(0), flow(0), reverse(0) {} + + ResidualEdge(int dst, int capacity, double cost, int flow, int reverse) + : dst(dst), capacity(capacity), cost(cost), flow(flow), reverse(reverse) + { + } +}; + +void SSP::maximizeLinearAssignment( + const std::vector> & cost, std::unordered_map * direct_assignment, + std::unordered_map * reverse_assignment) +{ + // NOTE: Need to set as default arguments + bool sparse_cost = true; + // bool sparse_cost = false; + + // Hyperparameters + // double MAX_COST = 6; + const double MAX_COST = 10; + const double INF_DIST = 10000000; + const double EPS = 1e-5; + + // When there is no agents or no tasks, terminate + if (cost.size() == 0 || cost.at(0).size() == 0) { + return; + } + + // Construct a bipartite graph from the cost matrix + int n_agents = cost.size(); + int n_tasks = cost.at(0).size(); + + int n_dummies; + if (sparse_cost) { + n_dummies = n_agents; + } else { + n_dummies = 0; + } + + int source = 0; + int sink = n_agents + n_tasks + 1; + int n_nodes = n_agents + n_tasks + n_dummies + 2; + + // // Print cost matrix + // std::cout << std::endl; + // for (int agent = 0; agent < n_agents; agent++) + // { + // for (int task = 0; task < n_tasks; task++) + // { + // std::cout << cost.at(agent).at(task) << " "; + // } + // std::cout << std::endl; + // } + + // std::chrono::system_clock::time_point start_time, end_time; + // start_time = std::chrono::system_clock::now(); + + // Adjacency list of residual graph (index: nodes) + // - 0: source node + // - {1, ..., n_agents}: agent nodes + // - {n_agents+1, ..., n_agents+n_tasks}: task nodes + // - n_agents+n_tasks+1: sink node + // - {n_agents+n_tasks+2, ..., n_agents+n_tasks+1+n_agents}: + // dummy node (when sparse_cost is true) + std::vector> adjacency_list(n_nodes); + + // Reserve memory + for (int v = 0; v < n_nodes; ++v) { + if (v == source) { + // Source + adjacency_list.at(v).reserve(n_agents); + } else if (v <= n_agents) { + // Agents + adjacency_list.at(v).reserve(n_tasks + 1 + 1); + } else if (v <= n_agents + n_tasks) { + // Tasks + adjacency_list.at(v).reserve(n_agents + 1); + } else if (v == sink) { + // Sink + adjacency_list.at(v).reserve(n_tasks + n_dummies); + } else { + // Dummies + adjacency_list.at(v).reserve(2); + } + } + + // Add edges form source + for (int agent = 0; agent < n_agents; ++agent) { + // From source to agent + adjacency_list.at(source).emplace_back(agent + 1, 1, 0, 0, adjacency_list.at(agent + 1).size()); + // From agent to source + adjacency_list.at(agent + 1).emplace_back( + source, 0, 0, 0, adjacency_list.at(source).size() - 1); + } + + // Add edges from agents + for (int agent = 0; agent < n_agents; ++agent) { + for (int task = 0; task < n_tasks; ++task) { + if (!sparse_cost || cost.at(agent).at(task) > EPS) { + // From agent to task + adjacency_list.at(agent + 1).emplace_back( + task + n_agents + 1, 1, MAX_COST - cost.at(agent).at(task), 0, + adjacency_list.at(task + n_agents + 1).size()); + + // From task to agent + adjacency_list.at(task + n_agents + 1) + .emplace_back( + agent + 1, 0, cost.at(agent).at(task) - MAX_COST, 0, + adjacency_list.at(agent + 1).size() - 1); + } + } + } + + // Add edges form tasks + for (int task = 0; task < n_tasks; ++task) { + // From task to sink + adjacency_list.at(task + n_agents + 1) + .emplace_back(sink, 1, 0, 0, adjacency_list.at(sink).size()); + + // From sink to task + adjacency_list.at(sink).emplace_back( + task + n_agents + 1, 0, 0, 0, adjacency_list.at(task + n_agents + 1).size() - 1); + } + + // Add edges from dummy + if (sparse_cost) { + for (int agent = 0; agent < n_agents; ++agent) { + // From agent to dummy + adjacency_list.at(agent + 1).emplace_back( + agent + n_agents + n_tasks + 2, 1, MAX_COST, 0, + adjacency_list.at(agent + n_agents + n_tasks + 2).size()); + + // From dummy to agent + adjacency_list.at(agent + n_agents + n_tasks + 2) + .emplace_back(agent + 1, 0, -MAX_COST, 0, adjacency_list.at(agent + 1).size() - 1); + + // From dummy to sink + adjacency_list.at(agent + n_agents + n_tasks + 2) + .emplace_back(sink, 1, 0, 0, adjacency_list.at(sink).size()); + + // From sink to dummy + adjacency_list.at(sink).emplace_back( + agent + n_agents + n_tasks + 2, 0, 0, 0, + adjacency_list.at(agent + n_agents + n_tasks + 2).size() - 1); + } + } + + // Maximum flow value + const int max_flow = std::min(n_agents, n_tasks); + + // Feasible potentials + std::vector potentials(n_nodes, 0); + + // Shortest path lengths + std::vector distances(n_nodes, INF_DIST); + + // Whether previously visited the node or not + std::vector is_visited(n_nodes, false); + + // Parent node () + std::vector> prev_values(n_nodes); + + for (int i = 0; i < max_flow; ++i) { + // Initialize priority queue () + std::priority_queue< + std::pair, std::vector>, + std::greater>> + p_queue; + + // Reset all trajectory states + if (i > 0) { + std::fill(distances.begin(), distances.end(), INF_DIST); + std::fill(is_visited.begin(), is_visited.end(), false); + } + + // Start trajectory from the source node + p_queue.push(std::make_pair(0, source)); + distances.at(source) = 0; + + while (!p_queue.empty()) { + // Get the next element + std::pair cur_elem = p_queue.top(); + // std::cout << "[pop]: (" << cur_elem.first << ", " << cur_elem.second << ")" << std::endl; + p_queue.pop(); + + double cur_node_dist = cur_elem.first; + int cur_node = cur_elem.second; + + // If already visited node, skip and continue + if (is_visited.at(cur_node)) { + continue; + } + assert(cur_node_dist == distances.at(cur_node)); + + // Mark as visited + is_visited.at(cur_node) = true; + // Update potential + potentials.at(cur_node) += cur_node_dist; + + // When reached to the sink node, terminate. + if (cur_node == sink) { + break; + } + + // Loop over the incident nodes(/edges) + for (auto it_incident_edge = adjacency_list.at(cur_node).cbegin(); + it_incident_edge != adjacency_list.at(cur_node).cend(); it_incident_edge++) { + // If the node is not visited and have capacity to increase flow, visit. + if (!is_visited.at(it_incident_edge->dst) && it_incident_edge->capacity > 0) { + // Calculate reduced cost + double reduced_cost = + it_incident_edge->cost + potentials.at(cur_node) - potentials.at(it_incident_edge->dst); + assert(reduced_cost >= 0); + if (distances.at(it_incident_edge->dst) > reduced_cost) { + distances.at(it_incident_edge->dst) = reduced_cost; + prev_values.at(it_incident_edge->dst) = + std::make_pair(cur_node, it_incident_edge - adjacency_list.at(cur_node).cbegin()); + // std::cout << "[push]: (" << reduced_cost << ", " << next_v << ")" << std::endl; + p_queue.push(std::make_pair(reduced_cost, it_incident_edge->dst)); + } + } + } + } + + // Shortest path length to sink is greater than MAX_COST, + // which means no non-dummy routes left, terminate + if (potentials.at(sink) >= MAX_COST) { + break; + } + + // Update potentials of unvisited nodes + for (int v = 0; v < n_nodes; ++v) { + if (!is_visited.at(v)) { + potentials.at(v) += distances.at(sink); + } + } + // //Print potentials + // for (int v = 0; v < n_nodes; ++v) + // { + // std::cout << potentials.at(v) << ", "; + // } + // std::cout << std::endl; + + // Increase/decrease flow and capacity along the shortest path from the source to the sink + int v = sink; + int prev_v; + while (v != source) { + ResidualEdge & e_forward = + adjacency_list.at(prev_values.at(v).first).at(prev_values.at(v).second); + assert(e_forward.dst == v); + ResidualEdge & e_backward = adjacency_list.at(v).at(e_forward.reverse); + prev_v = e_backward.dst; + + if (e_backward.flow == 0) { + // Increase flow + // State A + assert(e_forward.capacity == 1); + assert(e_forward.flow == 0); + assert(e_backward.capacity == 0); + assert(e_backward.flow == 0); + + e_forward.capacity -= 1; + e_forward.flow += 1; + e_backward.capacity += 1; + + // State B + assert(e_forward.capacity == 0); + assert(e_forward.flow == 1); + assert(e_backward.capacity == 1); + assert(e_backward.flow == 0); + } else { + // Decrease flow + // State B + assert(e_forward.capacity == 1); + assert(e_forward.flow == 0); + assert(e_backward.capacity == 0); + assert(e_backward.flow == 1); + + e_forward.capacity -= 1; + e_backward.capacity += 1; + e_backward.flow -= 1; + + // State A + assert(e_forward.capacity == 0); + assert(e_forward.flow == 0); + assert(e_backward.capacity == 1); + assert(e_backward.flow == 0); + } + + v = prev_v; + } + +#ifndef NDEBUG + // Check if the potentials are feasible potentials + for (int v = 0; v < n_nodes; ++v) { + for (auto it_incident_edge = adjacency_list.at(v).cbegin(); + it_incident_edge != adjacency_list.at(v).cend(); ++it_incident_edge) { + if (it_incident_edge->capacity > 0) { + double reduced_cost = + it_incident_edge->cost + potentials.at(v) - potentials.at(it_incident_edge->dst); + assert(reduced_cost >= 0); + } + } + } +#endif + } + + // Output + for (int agent = 0; agent < n_agents; ++agent) { + for (auto it_incident_edge = adjacency_list.at(agent + 1).cbegin(); + it_incident_edge != adjacency_list.at(agent + 1).cend(); ++it_incident_edge) { + int task = it_incident_edge->dst - (n_agents + 1); + + // If the flow value is 1 and task is not dummy, assign the task to the agent. + if (it_incident_edge->flow == 1 && 0 <= task && task < n_tasks) { + (*direct_assignment)[agent] = task; + (*reverse_assignment)[task] = agent; + break; + } + } + } + +#ifndef NDEBUG + // Check if the result is valid assignment + for (int agent = 0; agent < n_agents; ++agent) { + if (direct_assignment->find(agent) != direct_assignment->cend()) { + int task = (*direct_assignment).at(agent); + assert(direct_assignment->at(agent) == task); + assert(reverse_assignment->at(task) == agent); + } + } +#endif +} +} // namespace gnn_solver diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp new file mode 100644 index 0000000000000..d9f0d3ff44428 --- /dev/null +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -0,0 +1,386 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include "multi_object_tracker/multi_object_tracker_core.hpp" +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include +#include + +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + +namespace +{ +boost::optional getTransform( + const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, + const std::string & target_frame_id, const rclcpp::Time & time) +{ + try { + geometry_msgs::msg::TransformStamped self_transform_stamped; + self_transform_stamped = tf_buffer.lookupTransform( + /*target*/ target_frame_id, /*src*/ source_frame_id, time, + rclcpp::Duration::from_seconds(0.5)); + return self_transform_stamped.transform; + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("multi_object_tracker"), ex.what()); + return boost::none; + } +} + +bool transformDetectedObjects( + const autoware_auto_perception_msgs::msg::DetectedObjects & input_msg, + const std::string & target_frame_id, const tf2_ros::Buffer & tf_buffer, + autoware_auto_perception_msgs::msg::DetectedObjects & output_msg) +{ + output_msg = input_msg; + + /* transform to world coordinate */ + if (input_msg.header.frame_id != target_frame_id) { + output_msg.header.frame_id = target_frame_id; + tf2::Transform tf_target2objects_world; + tf2::Transform tf_target2objects; + tf2::Transform tf_objects_world2objects; + { + const auto ros_target2objects_world = + getTransform(tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); + if (!ros_target2objects_world) { + return false; + } + tf2::fromMsg(*ros_target2objects_world, tf_target2objects_world); + } + for (size_t i = 0; i < output_msg.objects.size(); ++i) { + tf2::fromMsg( + output_msg.objects.at(i).kinematics.pose_with_covariance.pose, tf_objects_world2objects); + tf_target2objects = tf_target2objects_world * tf_objects_world2objects; + tf2::toMsg(tf_target2objects, output_msg.objects.at(i).kinematics.pose_with_covariance.pose); + // TODO(yukkysaito) transform covariance + } + } + return true; +} + +inline float getVelocity(const autoware_auto_perception_msgs::msg::TrackedObject & object) +{ + return std::hypot( + object.kinematics.twist_with_covariance.twist.linear.x, + object.kinematics.twist_with_covariance.twist.linear.y); +} + +inline geometry_msgs::msg::Pose getPose( + const autoware_auto_perception_msgs::msg::TrackedObject & object) +{ + return object.kinematics.pose_with_covariance.pose; +} + +float getXYSquareDistance( + const geometry_msgs::msg::Transform & self_transform, + const autoware_auto_perception_msgs::msg::TrackedObject & object) +{ + const auto object_pos = getPose(object).position; + const float x = self_transform.translation.x - object_pos.x; + const float y = self_transform.translation.y - object_pos.y; + return x * x + y * y; +} + +/** + * @brief If the tracker is stable at a low speed and has a vehicle type, it will keep + * tracking for a longer time to deal with detection lost due to occlusion, etc. + * @param tracker The tracker to be determined. + * @param time Target time to determine. + * @param self_transform Position of the vehicle at the target time. + * @return Result of deciding whether to leave tracker or not. + */ +bool isSpecificAlivePattern( + const std::shared_ptr & tracker, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) +{ + autoware_auto_perception_msgs::msg::TrackedObject object; + tracker->getTrackedObject(time, object); + + constexpr float min_detection_rate = 0.2; + constexpr int min_measurement_count = 5; + constexpr float max_elapsed_time = 10.0; + constexpr float max_velocity = 1.0; + constexpr float max_distance = 100.0; + + const std::uint8_t label = tracker->getHighestProbLabel(); + + const float detection_rate = + tracker->getTotalMeasurementCount() / + (tracker->getTotalNoMeasurementCount() + tracker->getTotalMeasurementCount()); + + const bool big_vehicle = (label == Label::TRUCK || label == Label::BUS); + + const bool slow_velocity = getVelocity(object) < max_velocity; + + const bool high_confidence = + (min_detection_rate < detection_rate || + min_measurement_count < tracker->getTotalMeasurementCount()); + + const bool not_too_far = + getXYSquareDistance(self_transform, object) < max_distance * max_distance; + + const bool within_max_survival_period = + tracker->getElapsedTimeFromLastUpdate(time) < max_elapsed_time; + + const bool is_specific_alive_pattern = + high_confidence && big_vehicle && within_max_survival_period && not_too_far && slow_velocity; + + return is_specific_alive_pattern; +} + +} // namespace + +MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("multi_object_tracker", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_) +{ + // Create publishers and subscribers + detected_object_sub_ = create_subscription( + "input", rclcpp::QoS{1}, + std::bind(&MultiObjectTracker::onMeasurement, this, std::placeholders::_1)); + tracked_objects_pub_ = + create_publisher("output", rclcpp::QoS{1}); + + // Parameters + double publish_rate = declare_parameter("publish_rate", 30.0); + world_frame_id_ = declare_parameter("world_frame_id", "world"); + bool enable_delay_compensation{declare_parameter("enable_delay_compensation", false)}; + + auto cti = std::make_shared( + this->get_node_base_interface(), this->get_node_timers_interface()); + tf_buffer_.setCreateTimerInterface(cti); + + // Create ROS time based timer + if (enable_delay_compensation) { + auto timer_callback = std::bind(&MultiObjectTracker::onTimer, this); + auto period = std::chrono::duration_cast( + std::chrono::duration(1.0 / publish_rate)); + + publish_timer_ = std::make_shared>( + this->get_clock(), period, std::move(timer_callback), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(publish_timer_, nullptr); + } + + const auto tmp = this->declare_parameter>("can_assign_matrix"); + const std::vector can_assign_matrix(tmp.begin(), tmp.end()); + + const auto max_dist_matrix = this->declare_parameter>("max_dist_matrix"); + const auto max_area_matrix = this->declare_parameter>("max_area_matrix"); + const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); + const auto max_rad_matrix = this->declare_parameter>("max_rad_matrix"); + + data_association_ = std::make_unique( + can_assign_matrix, max_dist_matrix, max_area_matrix, min_area_matrix, max_rad_matrix); +} + +void MultiObjectTracker::onMeasurement( + const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) +{ + const auto self_transform = + getTransform(tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); + if (!self_transform) { + return; + } + + /* transform to world coordinate */ + autoware_auto_perception_msgs::msg::DetectedObjects transformed_objects; + if (!transformDetectedObjects( + *input_objects_msg, world_frame_id_, tf_buffer_, transformed_objects)) { + return; + } + /* tracker prediction */ + rclcpp::Time measurement_time = input_objects_msg->header.stamp; + for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { + (*itr)->predict(measurement_time); + } + + /* global nearest neighbor */ + std::unordered_map direct_assignment, reverse_assignment; + Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix( + transformed_objects, list_tracker_); // row : tracker, col : measurement + data_association_->assign(score_matrix, direct_assignment, reverse_assignment); + + /* tracker measurement update */ + int tracker_idx = 0; + for (auto tracker_itr = list_tracker_.begin(); tracker_itr != list_tracker_.end(); + ++tracker_itr, ++tracker_idx) { + if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found + (*(tracker_itr)) + ->updateWithMeasurement( + transformed_objects.objects.at(direct_assignment.find(tracker_idx)->second), + measurement_time); + } else { // not found + (*(tracker_itr))->updateWithoutMeasurement(); + } + } + + /* life cycle check */ + checkTrackerLifeCycle(list_tracker_, measurement_time, *self_transform); + /* sanitize trackers */ + sanitizeTracker(list_tracker_, measurement_time); + + /* new tracker */ + for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { + if (reverse_assignment.find(i) != reverse_assignment.end()) { // found + continue; + } + list_tracker_.push_back(createNewTracker(transformed_objects.objects.at(i), measurement_time)); + } + + if (publish_timer_ == nullptr) { + publish(measurement_time); + } +} + +std::shared_ptr MultiObjectTracker::createNewTracker( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & time) const +{ + const std::uint8_t label = utils::getHighestProbLabel(object.classification); + if (label == Label::CAR || label == Label::TRUCK || label == Label::BUS) { + return std::make_shared(time, object); + } else if (label == Label::PEDESTRIAN) { + return std::make_shared(time, object); + } else if (label == Label::BICYCLE || label == Label::MOTORCYCLE) { + return std::make_shared(time, object); + } else { + return std::make_shared(time, object); + } +} + +void MultiObjectTracker::onTimer() +{ + rclcpp::Time current_time = this->now(); + const auto self_transform = getTransform(tf_buffer_, world_frame_id_, "base_link", current_time); + if (!self_transform) { + return; + } + + /* life cycle check */ + checkTrackerLifeCycle(list_tracker_, current_time, *self_transform); + /* sanitize trackers */ + sanitizeTracker(list_tracker_, current_time); + + // Publish + publish(current_time); +} + +void MultiObjectTracker::checkTrackerLifeCycle( + std::list> & list_tracker, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) +{ + /* params */ + constexpr float max_elapsed_time = 1.0; + + /* delete tracker */ + for (auto itr = list_tracker.begin(); itr != list_tracker.end(); ++itr) { + const bool is_old = max_elapsed_time < (*itr)->getElapsedTimeFromLastUpdate(time); + const bool is_specific_alive_pattern = isSpecificAlivePattern(*itr, time, self_transform); + if (is_old && !is_specific_alive_pattern) { + auto erase_itr = itr; + --itr; + list_tracker.erase(erase_itr); + } + } +} + +void MultiObjectTracker::sanitizeTracker( + std::list> & list_tracker, const rclcpp::Time & time) +{ + constexpr float min_iou = 0.1; + constexpr double distance_threshold = 5.0; + /* delete collision tracker */ + for (auto itr1 = list_tracker.begin(); itr1 != list_tracker.end(); ++itr1) { + autoware_auto_perception_msgs::msg::TrackedObject object1; + (*itr1)->getTrackedObject(time, object1); + for (auto itr2 = std::next(itr1); itr2 != list_tracker.end(); ++itr2) { + autoware_auto_perception_msgs::msg::TrackedObject object2; + (*itr2)->getTrackedObject(time, object2); + const double distance = std::hypot( + object1.kinematics.pose_with_covariance.pose.position.x - + object2.kinematics.pose_with_covariance.pose.position.x, + object1.kinematics.pose_with_covariance.pose.position.y - + object2.kinematics.pose_with_covariance.pose.position.y); + if (distance_threshold < distance) { + continue; + } + if (min_iou < utils::get2dIoU(object1, object2)) { + if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { + itr1 = list_tracker.erase(itr1); + --itr1; + break; + } else { + itr2 = list_tracker.erase(itr2); + --itr2; + } + } + } + } +} + +inline bool MultiObjectTracker::shouldTrackerPublish( + const std::shared_ptr tracker) const +{ + constexpr int measurement_count_threshold = 3; + if (tracker->getTotalMeasurementCount() < measurement_count_threshold) { + return false; + } + return true; +} + +void MultiObjectTracker::publish(const rclcpp::Time & time) const +{ + const auto subscriber_count = tracked_objects_pub_->get_subscription_count() + + tracked_objects_pub_->get_intra_process_subscription_count(); + if (subscriber_count < 1) { + return; + } + // Create output msg + autoware_auto_perception_msgs::msg::TrackedObjects output_msg; + output_msg.header.frame_id = world_frame_id_; + output_msg.header.stamp = time; + for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { + if (!shouldTrackerPublish(*itr)) { + continue; + } + autoware_auto_perception_msgs::msg::TrackedObject object; + (*itr)->getTrackedObject(time, object); + output_msg.objects.push_back(object); + } + + // Publish + tracked_objects_pub_->publish(output_msg); +} + +RCLCPP_COMPONENTS_REGISTER_NODE(MultiObjectTracker) diff --git a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp new file mode 100644 index 0000000000000..5d34e995f2f27 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp @@ -0,0 +1,403 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include "multi_object_tracker/tracker/model/bicycle_tracker.hpp" + +#include "multi_object_tracker/utils/utils.hpp" + +#include + +#include +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include +#include + +BicycleTracker::BicycleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + logger_(rclcpp::get_logger("BicycleTracker")), + last_update_time_(time), + z_(object.kinematics.pose_with_covariance.pose.position.z) +{ + object_ = object; + + // initialize params + ekf_params_.use_measurement_covariance = false; + float q_stddev_x = 0.0; // [m/s] + float q_stddev_y = 0.0; // [m/s] + float q_stddev_yaw = autoware_utils::deg2rad(10); // [rad/s] + float q_stddev_vx = autoware_utils::kmph2mps(10); // [m/(s*s)] + float q_stddev_wz = autoware_utils::deg2rad(25); // [rad/(s*s)] + float r_stddev_x = 0.6; // [m] + float r_stddev_y = 0.4; // [m] + float r_stddev_yaw = autoware_utils::deg2rad(30); // [rad] + float p0_stddev_x = 0.8; // [m/s] + float p0_stddev_y = 0.5; // [m/s] + float p0_stddev_yaw = autoware_utils::deg2rad(1000); // [rad/s] + float p0_stddev_vx = autoware_utils::kmph2mps(1000); // [m/(s*s)] + float p0_stddev_wz = autoware_utils::deg2rad(10); // [rad/(s*s)] + ekf_params_.q_cov_x = std::pow(q_stddev_x, 2.0); + ekf_params_.q_cov_y = std::pow(q_stddev_y, 2.0); + ekf_params_.q_cov_yaw = std::pow(q_stddev_yaw, 2.0); + ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); + ekf_params_.q_cov_wz = std::pow(q_stddev_wz, 2.0); + ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); + ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); + ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); + ekf_params_.p0_cov_x = std::pow(p0_stddev_x, 2.0); + ekf_params_.p0_cov_y = std::pow(p0_stddev_y, 2.0); + ekf_params_.p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + ekf_params_.p0_cov_vx = std::pow(p0_stddev_vx, 2.0); + ekf_params_.p0_cov_wz = std::pow(p0_stddev_wz, 2.0); + max_vx_ = autoware_utils::kmph2mps(100); // [m/s] + max_wz_ = autoware_utils::deg2rad(30); // [rad/s] + + // initialize X matrix + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + X(IDX::X) = object.kinematics.pose_with_covariance.pose.position.x; + X(IDX::Y) = object.kinematics.pose_with_covariance.pose.position.y; + X(IDX::YAW) = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + if (object.kinematics.has_twist) { + X(IDX::VX) = object.kinematics.twist_with_covariance.twist.linear.x; + X(IDX::WZ) = object.kinematics.twist_with_covariance.twist.angular.z; + } else { + X(IDX::VX) = 0.0; + X(IDX::WZ) = 0.0; + } + + // initialize P matrix + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] == 0.0) { + const double cos_yaw = std::cos(X(IDX::YAW)); + const double sin_yaw = std::sin(X(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X(IDX::YAW)); + // Rotate the covariance matrix according to the vehicle yaw + // because p0_cov_x and y are in the vehicle coordinate system. + P(IDX::X, IDX::X) = + ekf_params_.p0_cov_x * cos_yaw * cos_yaw + ekf_params_.p0_cov_y * sin_yaw * sin_yaw; + P(IDX::X, IDX::Y) = 0.5f * (ekf_params_.p0_cov_x - ekf_params_.p0_cov_y) * sin_2yaw; + P(IDX::Y, IDX::Y) = + ekf_params_.p0_cov_x * sin_yaw * sin_yaw + ekf_params_.p0_cov_y * cos_yaw * cos_yaw; + P(IDX::Y, IDX::X) = P(IDX::X, IDX::Y); + P(IDX::YAW, IDX::YAW) = ekf_params_.p0_cov_yaw; + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } else { + P(IDX::X, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::X, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + P(IDX::Y, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P(IDX::Y, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + P(IDX::YAW, IDX::YAW) = + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + if (object.kinematics.has_twist_covariance) { + P(IDX::VX, IDX::VX) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::WZ, IDX::WZ) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } else { + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } + } + + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_ = { + object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; + } else { + bounding_box_ = {1.0, 0.5, 1.7}; + } + ekf_.init(X, P); +} + +bool BicycleTracker::predict(const rclcpp::Time & time) +{ + const double dt = (time - last_update_time_).seconds(); + bool ret = predict(dt, ekf_); + if (ret) { + last_update_time_ = time; + } + return ret; +} + +bool BicycleTracker::predict(const double dt, KalmanFilter & ekf) const +{ + /* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * cos(yaw_k) * dt + * y_{k+1} = y_k + vx_k * sin(yaw_k) * dt + * yaw_{k+1} = yaw_k + (wz_k) * dt + * vx_{k+1} = vx_k + * wz_{k+1} = wz_k + * + */ + + /* == Linearized model == + * + * A = [ 1, 0, -vx*sin(yaw)*dt, cos(yaw)*dt, 0] + * [ 0, 1, vx*cos(yaw)*dt, sin(yaw)*dt, 0] + * [ 0, 0, 1, 0, dt] + * [ 0, 0, 0, 1, 0] + * [ 0, 0, 0, 0, 1] + */ + + // X t + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + ekf.getX(X_t); + const double cos_yaw = std::cos(X_t(IDX::YAW)); + const double sin_yaw = std::sin(X_t(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X_t(IDX::YAW)); + + // X t+1 + Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); // predicted state + X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VX) * cos_yaw * dt; // dx = v * cos(yaw) + X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VX) * sin_yaw * dt; // dy = v * sin(yaw) + X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ)) * dt; // dyaw = omega + X_next_t(IDX::VX) = X_t(IDX::VX); + X_next_t(IDX::WZ) = X_t(IDX::WZ); + + // A + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); + A(IDX::X, IDX::YAW) = -X_t(IDX::VX) * sin_yaw * dt; + A(IDX::X, IDX::VX) = cos_yaw * dt; + A(IDX::Y, IDX::YAW) = X_t(IDX::VX) * cos_yaw * dt; + A(IDX::Y, IDX::VX) = sin_yaw * dt; + A(IDX::YAW, IDX::WZ) = dt; + + // Q + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + // Rotate the covariance matrix according to the vehicle yaw + // because q_cov_x and y are in the vehicle coordinate system. + Q(IDX::X, IDX::X) = + (ekf_params_.q_cov_x * cos_yaw * cos_yaw + ekf_params_.q_cov_y * sin_yaw * sin_yaw) * dt * dt; + Q(IDX::X, IDX::Y) = (0.5f * (ekf_params_.q_cov_x - ekf_params_.q_cov_y) * sin_2yaw) * dt * dt; + Q(IDX::Y, IDX::Y) = + (ekf_params_.q_cov_x * sin_yaw * sin_yaw + ekf_params_.q_cov_y * cos_yaw * cos_yaw) * dt * dt; + Q(IDX::Y, IDX::X) = Q(IDX::X, IDX::Y); + Q(IDX::YAW, IDX::YAW) = ekf_params_.q_cov_yaw * dt * dt; + Q(IDX::VX, IDX::VX) = ekf_params_.q_cov_vx * dt * dt; + Q(IDX::WZ, IDX::WZ) = ekf_params_.q_cov_wz * dt * dt; + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(ekf_params_.dim_x, 1); + + if (!ekf.predict(X_next_t, A, Q)) { + RCLCPP_WARN(logger_, "Cannot predict"); + } + + return true; +} + +bool BicycleTracker::measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + constexpr int dim_y = 2; // pos x, pos y, depending on Pose output + // double measurement_yaw = + // autoware_utils::normalizeRadian(tf2::getYaw(object.state.pose_covariance.pose.orientation)); + // { + // Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + // ekf_.getX(X_t); + // while (M_PI_2 <= X_t(IDX::YAW) - measurement_yaw) { + // measurement_yaw = measurement_yaw + M_PI; + // } + // while (M_PI_2 <= measurement_yaw - X_t(IDX::YAW)) { + // measurement_yaw = measurement_yaw - M_PI; + // } + // float theta = std::acos( + // std::cos(X_t(IDX::YAW)) * std::cos(measurement_yaw) + + // std::sin(X_t(IDX::YAW)) * std::sin(measurement_yaw)); + // if (autoware_utils::deg2rad(60) < std::fabs(theta)) return false; + // } + + /* Set measurement matrix */ + Eigen::MatrixXd Y(dim_y, 1); + Y << object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y; + + /* Set measurement matrix */ + Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, ekf_params_.dim_x); + C(0, IDX::X) = 1.0; // for pos x + C(1, IDX::Y) = 1.0; // for pos y + // C(2, IDX::YAW) = 1.0; // for yaw + + /* Set measurement noise covariance */ + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0) { + R(0, 0) = ekf_params_.r_cov_x; // x - x + R(0, 1) = 0.0; // x - y + R(1, 1) = ekf_params_.r_cov_y; // y - y + R(1, 0) = R(0, 1); // y - x + // R(2, 2) = ekf_params_.r_cov_yaw; // yaw - yaw + } else { + R(0, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + R(0, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + // R(0, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW]; + R(1, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + R(1, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + // R(1, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_YAW]; + // R(2, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X]; + // R(2, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_Y]; + // R(2, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } + if (!ekf_.update(Y, C, R)) { + RCLCPP_WARN(logger_, "Cannot update"); + } + + // normalize yaw and limit vx, wz + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + Eigen::MatrixXd P_t(ekf_params_.dim_x, ekf_params_.dim_x); + ekf_.getX(X_t); + ekf_.getP(P_t); + X_t(IDX::YAW) = autoware_utils::normalizeRadian(X_t(IDX::YAW)); + if (!(-max_vx_ <= X_t(IDX::VX) && X_t(IDX::VX) <= max_vx_)) { + X_t(IDX::VX) = X_t(IDX::VX) < 0 ? -max_vx_ : max_vx_; + } + if (!(-max_wz_ <= X_t(IDX::WZ) && X_t(IDX::WZ) <= max_wz_)) { + X_t(IDX::WZ) = X_t(IDX::WZ) < 0 ? -max_wz_ : max_wz_; + } + ekf_.init(X_t, P_t); + } + + // position z + constexpr float gain = 0.9; + z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; + + return true; +} + +bool BicycleTracker::measureWithShape( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return false; + } + constexpr float gain = 0.9; + + bounding_box_.width = gain * bounding_box_.width + (1.0 - gain) * object.shape.dimensions.x; + bounding_box_.length = gain * bounding_box_.length + (1.0 - gain) * object.shape.dimensions.y; + bounding_box_.height = gain * bounding_box_.height + (1.0 - gain) * object.shape.dimensions.z; + + return true; +} + +bool BicycleTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + object_ = object; + + if (0.01 /*10msec*/ < std::fabs((time - last_update_time_).seconds())) { + RCLCPP_WARN( + logger_, "There is a large gap between predicted time and measurement time. (%f)", + (time - last_update_time_).seconds()); + } + + measureWithPose(object); + measureWithShape(object); + + return true; +} + +bool BicycleTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + object = utils::toTrackedObject(object_); + object.object_id = getUUID(); + object.classification = getClassification(); + + // predict kinematics + KalmanFilter tmp_ekf_for_no_update = ekf_; + const double dt = (time - last_update_time_).seconds(); + if (0.001 /*1msec*/ < dt) { + predict(dt, tmp_ekf_for_no_update); + } + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + Eigen::MatrixXd P(ekf_params_.dim_x, ekf_params_.dim_x); // predicted state + tmp_ekf_for_no_update.getX(X_t); + tmp_ekf_for_no_update.getP(P); + + // position + object.kinematics.pose_with_covariance.pose.position.x = X_t(IDX::X); + object.kinematics.pose_with_covariance.pose.position.y = X_t(IDX::Y); + object.kinematics.pose_with_covariance.pose.position.z = z_; + // quaternion + { + double roll, pitch, yaw; + tf2::Quaternion original_quaternion; + tf2::fromMsg(object_.kinematics.pose_with_covariance.pose.orientation, original_quaternion); + tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw); + tf2::Quaternion filtered_quaternion; + filtered_quaternion.setRPY(roll, pitch, X_t(IDX::YAW)); + object.kinematics.pose_with_covariance.pose.orientation.x = filtered_quaternion.x(); + object.kinematics.pose_with_covariance.pose.orientation.y = filtered_quaternion.y(); + object.kinematics.pose_with_covariance.pose.orientation.z = filtered_quaternion.z(); + object.kinematics.pose_with_covariance.pose.orientation.w = filtered_quaternion.w(); + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } + // position covariance + constexpr double z_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double r_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double p_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::X, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y] = P(IDX::X, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X] = P(IDX::Y, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = z_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = r_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = p_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::YAW, IDX::YAW); + + // twist + object.kinematics.twist_with_covariance.twist.linear.x = X_t(IDX::VX); + object.kinematics.twist_with_covariance.twist.angular.z = X_t(IDX::WZ); + // twist covariance + constexpr double vy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double vz_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wx_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::VX, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = vy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = vz_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW] = + P(IDX::VX, IDX::WZ); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X] = + P(IDX::WZ, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = wx_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = wy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::WZ, IDX::WZ); + + // set shape + object.shape.dimensions.x = bounding_box_.width; + object.shape.dimensions.y = bounding_box_.length; + object.shape.dimensions.z = bounding_box_.height; + + return true; +} diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp new file mode 100644 index 0000000000000..19cee1613a2c5 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -0,0 +1,421 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include "multi_object_tracker/tracker/model/big_vehicle_tracker.hpp" +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include +#include + +BigVehicleTracker::BigVehicleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + logger_(rclcpp::get_logger("BigVehicleTracker")), + last_update_time_(time), + z_(object.kinematics.pose_with_covariance.pose.position.z) +{ + object_ = object; + + // initialize params + ekf_params_.use_measurement_covariance = false; + float q_stddev_x = 0.0; // [m/s] + float q_stddev_y = 0.0; // [m/s] + float q_stddev_yaw = autoware_utils::deg2rad(20); // [rad/s] + float q_stddev_vx = autoware_utils::kmph2mps(10); // [m/(s*s)] + float q_stddev_wz = autoware_utils::deg2rad(20); // [rad/(s*s)] + float r_stddev_x = 1.5; // [m] + float r_stddev_y = 0.5; // [m] + float r_stddev_yaw = autoware_utils::deg2rad(30); // [rad] + float p0_stddev_x = 1.5; // [m] + float p0_stddev_y = 0.5; // [m] + float p0_stddev_yaw = autoware_utils::deg2rad(30); // [rad] + float p0_stddev_vx = autoware_utils::kmph2mps(1000); // [m/s] + float p0_stddev_wz = autoware_utils::deg2rad(10); // [rad/s] + ekf_params_.q_cov_x = std::pow(q_stddev_x, 2.0); + ekf_params_.q_cov_y = std::pow(q_stddev_y, 2.0); + ekf_params_.q_cov_yaw = std::pow(q_stddev_yaw, 2.0); + ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); + ekf_params_.q_cov_wz = std::pow(q_stddev_wz, 2.0); + ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); + ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); + ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); + ekf_params_.p0_cov_x = std::pow(p0_stddev_x, 2.0); + ekf_params_.p0_cov_y = std::pow(p0_stddev_y, 2.0); + ekf_params_.p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + ekf_params_.p0_cov_vx = std::pow(p0_stddev_vx, 2.0); + ekf_params_.p0_cov_wz = std::pow(p0_stddev_wz, 2.0); + max_vx_ = autoware_utils::kmph2mps(100); // [m/s] + max_wz_ = autoware_utils::deg2rad(30); // [rad/s] + + // initialize X matrix + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + X(IDX::X) = object.kinematics.pose_with_covariance.pose.position.x; + X(IDX::Y) = object.kinematics.pose_with_covariance.pose.position.y; + X(IDX::YAW) = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + if (object.kinematics.has_twist) { + X(IDX::VX) = object.kinematics.twist_with_covariance.twist.linear.x; + X(IDX::WZ) = object.kinematics.twist_with_covariance.twist.angular.z; + } else { + X(IDX::VX) = 0.0; + X(IDX::WZ) = 0.0; + } + + // initialize P matrix + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] == 0.0) { + const double cos_yaw = std::cos(X(IDX::YAW)); + const double sin_yaw = std::sin(X(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X(IDX::YAW)); + // Rotate the covariance matrix according to the vehicle yaw + // because p0_cov_x and y are in the vehicle coordinate system. + P(IDX::X, IDX::X) = + ekf_params_.p0_cov_x * cos_yaw * cos_yaw + ekf_params_.p0_cov_y * sin_yaw * sin_yaw; + P(IDX::X, IDX::Y) = 0.5f * (ekf_params_.p0_cov_x - ekf_params_.p0_cov_y) * sin_2yaw; + P(IDX::Y, IDX::Y) = + ekf_params_.p0_cov_x * sin_yaw * sin_yaw + ekf_params_.p0_cov_y * cos_yaw * cos_yaw; + P(IDX::Y, IDX::X) = P(IDX::X, IDX::Y); + P(IDX::YAW, IDX::YAW) = ekf_params_.p0_cov_yaw; + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } else { + P(IDX::X, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::X, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + P(IDX::Y, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P(IDX::Y, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + P(IDX::YAW, IDX::YAW) = + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + if (object.kinematics.has_twist_covariance) { + P(IDX::VX, IDX::VX) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::WZ, IDX::WZ) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } else { + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } + } + + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_ = { + object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; + } else { + bounding_box_ = {2.0, 7.0, 2.0}; + } + ekf_.init(X, P); +} + +bool BigVehicleTracker::predict(const rclcpp::Time & time) +{ + const double dt = (time - last_update_time_).seconds(); + bool ret = predict(dt, ekf_); + if (ret) { + last_update_time_ = time; + } + return ret; +} + +bool BigVehicleTracker::predict(const double dt, KalmanFilter & ekf) const +{ + /* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * cos(yaw_k) * dt + * y_{k+1} = y_k + vx_k * sin(yaw_k) * dt + * yaw_{k+1} = yaw_k + (wz_k) * dt + * vx_{k+1} = vx_k + * wz_{k+1} = wz_k + * + */ + + /* == Linearized model == + * + * A = [ 1, 0, -vx*sin(yaw)*dt, cos(yaw)*dt, 0] + * [ 0, 1, vx*cos(yaw)*dt, sin(yaw)*dt, 0] + * [ 0, 0, 1, 0, dt] + * [ 0, 0, 0, 1, 0] + * [ 0, 0, 0, 0, 1] + */ + + // X t + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + ekf.getX(X_t); + const double cos_yaw = std::cos(X_t(IDX::YAW)); + const double sin_yaw = std::sin(X_t(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X_t(IDX::YAW)); + + // X t+1 + Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); // predicted state + X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VX) * cos_yaw * dt; // dx = v * cos(yaw) + X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VX) * sin_yaw * dt; // dy = v * sin(yaw) + X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ)) * dt; // dyaw = omega + X_next_t(IDX::VX) = X_t(IDX::VX); + X_next_t(IDX::WZ) = X_t(IDX::WZ); + + // A + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); + A(IDX::X, IDX::YAW) = -X_t(IDX::VX) * sin_yaw * dt; + A(IDX::X, IDX::VX) = cos_yaw * dt; + A(IDX::Y, IDX::YAW) = X_t(IDX::VX) * cos_yaw * dt; + A(IDX::Y, IDX::VX) = sin_yaw * dt; + A(IDX::YAW, IDX::WZ) = dt; + + // Q + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + // Rotate the covariance matrix according to the vehicle yaw + // because q_cov_x and y are in the vehicle coordinate system. + Q(IDX::X, IDX::X) = + (ekf_params_.q_cov_x * cos_yaw * cos_yaw + ekf_params_.q_cov_y * sin_yaw * sin_yaw) * dt * dt; + Q(IDX::X, IDX::Y) = (0.5f * (ekf_params_.q_cov_x - ekf_params_.q_cov_y) * sin_2yaw) * dt * dt; + Q(IDX::Y, IDX::Y) = + (ekf_params_.q_cov_x * sin_yaw * sin_yaw + ekf_params_.q_cov_y * cos_yaw * cos_yaw) * dt * dt; + Q(IDX::Y, IDX::X) = Q(IDX::X, IDX::Y); + Q(IDX::YAW, IDX::YAW) = ekf_params_.q_cov_yaw * dt * dt; + Q(IDX::VX, IDX::VX) = ekf_params_.q_cov_vx * dt * dt; + Q(IDX::WZ, IDX::WZ) = ekf_params_.q_cov_wz * dt * dt; + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(ekf_params_.dim_x, 1); + + if (!ekf.predict(X_next_t, A, Q)) { + RCLCPP_WARN(logger_, "Cannot predict"); + } + + return true; +} + +bool BigVehicleTracker::measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + + float r_cov_x; + float r_cov_y; + const uint8_t label = utils::getHighestProbLabel(object.classification); + + if (label == Label::CAR) { + constexpr float r_stddev_x = 8.0; // [m] + constexpr float r_stddev_y = 0.8; // [m] + r_cov_x = std::pow(r_stddev_x, 2.0); + r_cov_y = std::pow(r_stddev_y, 2.0); + } else if (label == Label::TRUCK || label == Label::BUS) { + r_cov_x = ekf_params_.r_cov_x; + r_cov_y = ekf_params_.r_cov_y; + } else { + r_cov_x = ekf_params_.r_cov_x; + r_cov_y = ekf_params_.r_cov_y; + } + + constexpr int dim_y = 3; // pos x, pos y, yaw, depending on Pose output + double measurement_yaw = autoware_utils::normalizeRadian( + tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + ekf_.getX(X_t); + // Fixed measurement_yaw to be in the range of +-90 degrees of X_t(IDX::YAW) + while (M_PI_2 <= X_t(IDX::YAW) - measurement_yaw) { + measurement_yaw = measurement_yaw + M_PI; + } + while (M_PI_2 <= measurement_yaw - X_t(IDX::YAW)) { + measurement_yaw = measurement_yaw - M_PI; + } + } + + /* Set measurement matrix */ + Eigen::MatrixXd Y(dim_y, 1); + Y << object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y, measurement_yaw; + + /* Set measurement matrix */ + Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, ekf_params_.dim_x); + C(0, IDX::X) = 1.0; // for pos x + C(1, IDX::Y) = 1.0; // for pos y + C(2, IDX::YAW) = 1.0; // for yaw + + /* Set measurement noise covariance */ + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] == 0.0) { + const double cos_yaw = std::cos(measurement_yaw); + const double sin_yaw = std::sin(measurement_yaw); + const double sin_2yaw = std::sin(2.0f * measurement_yaw); + R(0, 0) = r_cov_x * cos_yaw * cos_yaw + r_cov_y * sin_yaw * sin_yaw; // x - x + R(0, 1) = 0.5f * (r_cov_x - r_cov_y) * sin_2yaw; // x - y + R(1, 1) = r_cov_x * sin_yaw * sin_yaw + r_cov_y * cos_yaw * cos_yaw; // y - y + R(1, 0) = R(0, 1); // y - x + R(2, 2) = ekf_params_.r_cov_yaw; // yaw - yaw + } else { + R(0, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + R(0, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + R(0, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW]; + R(1, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + R(1, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + R(1, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_YAW]; + R(2, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X]; + R(2, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_Y]; + R(2, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } + if (!ekf_.update(Y, C, R)) { + RCLCPP_WARN(logger_, "Cannot update"); + } + + // normalize yaw and limit vx, wz + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + Eigen::MatrixXd P_t(ekf_params_.dim_x, ekf_params_.dim_x); + ekf_.getX(X_t); + ekf_.getP(P_t); + X_t(IDX::YAW) = autoware_utils::normalizeRadian(X_t(IDX::YAW)); + if (!(-max_vx_ <= X_t(IDX::VX) && X_t(IDX::VX) <= max_vx_)) { + X_t(IDX::VX) = X_t(IDX::VX) < 0 ? -max_vx_ : max_vx_; + } + if (!(-max_wz_ <= X_t(IDX::WZ) && X_t(IDX::WZ) <= max_wz_)) { + X_t(IDX::WZ) = X_t(IDX::WZ) < 0 ? -max_wz_ : max_wz_; + } + ekf_.init(X_t, P_t); + } + + // position z + constexpr float gain = 0.9; + z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; + + return true; +} + +bool BigVehicleTracker::measureWithShape( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return false; + } + constexpr float gain = 0.9; + + bounding_box_.width = gain * bounding_box_.width + (1.0 - gain) * object.shape.dimensions.x; + bounding_box_.length = gain * bounding_box_.length + (1.0 - gain) * object.shape.dimensions.y; + bounding_box_.height = gain * bounding_box_.height + (1.0 - gain) * object.shape.dimensions.z; + + return true; +} + +bool BigVehicleTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + object_ = object; + + if (0.01 /*10msec*/ < std::fabs((time - last_update_time_).seconds())) { + RCLCPP_WARN( + logger_, "There is a large gap between predicted time and measurement time. (%f)", + (time - last_update_time_).seconds()); + } + + measureWithPose(object); + measureWithShape(object); + + return true; +} + +bool BigVehicleTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + object = utils::toTrackedObject(object_); + object.object_id = getUUID(); + object.classification = getClassification(); + + // predict state + KalmanFilter tmp_ekf_for_no_update = ekf_; + const double dt = (time - last_update_time_).seconds(); + if (0.001 /*1msec*/ < dt) { + predict(dt, tmp_ekf_for_no_update); + } + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + Eigen::MatrixXd P(ekf_params_.dim_x, ekf_params_.dim_x); // predicted state + tmp_ekf_for_no_update.getX(X_t); + tmp_ekf_for_no_update.getP(P); + + // position + object.kinematics.pose_with_covariance.pose.position.x = X_t(IDX::X); + object.kinematics.pose_with_covariance.pose.position.y = X_t(IDX::Y); + object.kinematics.pose_with_covariance.pose.position.z = z_; + // quaternion + { + double roll, pitch, yaw; + tf2::Quaternion original_quaternion; + tf2::fromMsg(object_.kinematics.pose_with_covariance.pose.orientation, original_quaternion); + tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw); + tf2::Quaternion filtered_quaternion; + filtered_quaternion.setRPY(roll, pitch, X_t(IDX::YAW)); + object.kinematics.pose_with_covariance.pose.orientation.x = filtered_quaternion.x(); + object.kinematics.pose_with_covariance.pose.orientation.y = filtered_quaternion.y(); + object.kinematics.pose_with_covariance.pose.orientation.z = filtered_quaternion.z(); + object.kinematics.pose_with_covariance.pose.orientation.w = filtered_quaternion.w(); + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } + // position covariance + constexpr double z_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double r_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double p_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::X, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y] = P(IDX::X, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X] = P(IDX::Y, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = z_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = r_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = p_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::YAW, IDX::YAW); + + // twist + object.kinematics.twist_with_covariance.twist.linear.x = X_t(IDX::VX); + object.kinematics.twist_with_covariance.twist.angular.z = X_t(IDX::WZ); + // twist covariance + constexpr double vy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double vz_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wx_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::VX, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = vy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = vz_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW] = + P(IDX::VX, IDX::WZ); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X] = + P(IDX::WZ, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = wx_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = wy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::WZ, IDX::WZ); + + // set shape + object.shape.dimensions.x = bounding_box_.width; + object.shape.dimensions.y = bounding_box_.length; + object.shape.dimensions.z = bounding_box_.height; + + return true; +} diff --git a/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp new file mode 100644 index 0000000000000..1444ede87bf38 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp @@ -0,0 +1,61 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include "multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp" + +#include + +MultipleVehicleTracker::MultipleVehicleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + normal_vehicle_tracker_(time, object), + big_vehicle_tracker_(time, object) +{ +} + +bool MultipleVehicleTracker::predict(const rclcpp::Time & time) +{ + big_vehicle_tracker_.predict(time); + normal_vehicle_tracker_.predict(time); + return true; +} + +bool MultipleVehicleTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + big_vehicle_tracker_.measure(object, time); + normal_vehicle_tracker_.measure(object, time); + setClassification(object.classification); + return true; +} + +bool MultipleVehicleTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + const uint8_t label = getHighestProbLabel(); + + if (label == Label::CAR) { + normal_vehicle_tracker_.getTrackedObject(time, object); + } else if (label == Label::BUS || label == Label::TRUCK) { + big_vehicle_tracker_.getTrackedObject(time, object); + } + object.object_id = getUUID(); + object.classification = getClassification(); + return true; +} diff --git a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp new file mode 100644 index 0000000000000..907a28c9b5582 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp @@ -0,0 +1,421 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include "multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp" +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include +#include + +NormalVehicleTracker::NormalVehicleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + logger_(rclcpp::get_logger("NormalVehicleTracker")), + last_update_time_(time), + z_(object.kinematics.pose_with_covariance.pose.position.z) +{ + object_ = object; + + // initialize params + ekf_params_.use_measurement_covariance = false; + float q_stddev_x = 0.0; // object coordinate [m/s] + float q_stddev_y = 0.0; // object coordinate [m/s] + float q_stddev_yaw = autoware_utils::deg2rad(20); // map coordinate[rad/s] + float q_stddev_vx = autoware_utils::kmph2mps(10); // object coordinate [m/(s*s)] + float q_stddev_wz = autoware_utils::deg2rad(20); // object coordinate [rad/(s*s)] + float r_stddev_x = 1.0; // object coordinate [m] + float r_stddev_y = 0.3; // object coordinate [m] + float r_stddev_yaw = autoware_utils::deg2rad(30); // map coordinate [rad] + float p0_stddev_x = 1.0; // object coordinate [m/s] + float p0_stddev_y = 0.3; // object coordinate [m/s] + float p0_stddev_yaw = autoware_utils::deg2rad(30); // map coordinate [rad] + float p0_stddev_vx = autoware_utils::kmph2mps(1000); // object coordinate [m/s] + float p0_stddev_wz = autoware_utils::deg2rad(10); // object coordinate [rad/s] + ekf_params_.q_cov_x = std::pow(q_stddev_x, 2.0); + ekf_params_.q_cov_y = std::pow(q_stddev_y, 2.0); + ekf_params_.q_cov_yaw = std::pow(q_stddev_yaw, 2.0); + ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); + ekf_params_.q_cov_wz = std::pow(q_stddev_wz, 2.0); + ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); + ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); + ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); + ekf_params_.p0_cov_x = std::pow(p0_stddev_x, 2.0); + ekf_params_.p0_cov_y = std::pow(p0_stddev_y, 2.0); + ekf_params_.p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + ekf_params_.p0_cov_vx = std::pow(p0_stddev_vx, 2.0); + ekf_params_.p0_cov_wz = std::pow(p0_stddev_wz, 2.0); + max_vx_ = autoware_utils::kmph2mps(100); // [m/s] + max_wz_ = autoware_utils::deg2rad(30); // [rad/s] + + // initialize X matrix + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + X(IDX::X) = object.kinematics.pose_with_covariance.pose.position.x; + X(IDX::Y) = object.kinematics.pose_with_covariance.pose.position.y; + X(IDX::YAW) = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + if (object.kinematics.has_twist) { + X(IDX::VX) = object.kinematics.twist_with_covariance.twist.linear.x; + X(IDX::WZ) = object.kinematics.twist_with_covariance.twist.angular.z; + } else { + X(IDX::VX) = 0.0; + X(IDX::WZ) = 0.0; + } + + // initialize P matrix + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] == 0.0) { + const double cos_yaw = std::cos(X(IDX::YAW)); + const double sin_yaw = std::sin(X(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X(IDX::YAW)); + // Rotate the covariance matrix according to the vehicle yaw + // because p0_cov_x and y are in the vehicle coordinate system. + P(IDX::X, IDX::X) = + ekf_params_.p0_cov_x * cos_yaw * cos_yaw + ekf_params_.p0_cov_y * sin_yaw * sin_yaw; + P(IDX::X, IDX::Y) = 0.5f * (ekf_params_.p0_cov_x - ekf_params_.p0_cov_y) * sin_2yaw; + P(IDX::Y, IDX::Y) = + ekf_params_.p0_cov_x * sin_yaw * sin_yaw + ekf_params_.p0_cov_y * cos_yaw * cos_yaw; + P(IDX::Y, IDX::X) = P(IDX::X, IDX::Y); + P(IDX::YAW, IDX::YAW) = ekf_params_.p0_cov_yaw; + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } else { + P(IDX::X, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::X, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + P(IDX::Y, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P(IDX::Y, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + P(IDX::YAW, IDX::YAW) = + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + if (object.kinematics.has_twist_covariance) { + P(IDX::VX, IDX::VX) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::WZ, IDX::WZ) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } else { + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } + } + + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_ = { + object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; + } else { + bounding_box_ = {1.7, 4.0, 2.0}; + } + ekf_.init(X, P); +} + +bool NormalVehicleTracker::predict(const rclcpp::Time & time) +{ + const double dt = (time - last_update_time_).seconds(); + bool ret = predict(dt, ekf_); + if (ret) { + last_update_time_ = time; + } + return ret; +} + +bool NormalVehicleTracker::predict(const double dt, KalmanFilter & ekf) const +{ + /* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * cos(yaw_k) * dt + * y_{k+1} = y_k + vx_k * sin(yaw_k) * dt + * yaw_{k+1} = yaw_k + (wz_k) * dt + * vx_{k+1} = vx_k + * wz_{k+1} = wz_k + * + */ + + /* == Linearized model == + * + * A = [ 1, 0, -vx*sin(yaw)*dt, cos(yaw)*dt, 0] + * [ 0, 1, vx*cos(yaw)*dt, sin(yaw)*dt, 0] + * [ 0, 0, 1, 0, dt] + * [ 0, 0, 0, 1, 0] + * [ 0, 0, 0, 0, 1] + */ + + // X t + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + ekf.getX(X_t); + const double cos_yaw = std::cos(X_t(IDX::YAW)); + const double sin_yaw = std::sin(X_t(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X_t(IDX::YAW)); + + // X t+1 + Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); // predicted state + X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VX) * cos_yaw * dt; // dx = v * cos(yaw) + X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VX) * sin_yaw * dt; // dy = v * sin(yaw) + X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ)) * dt; // dyaw = omega + X_next_t(IDX::VX) = X_t(IDX::VX); + X_next_t(IDX::WZ) = X_t(IDX::WZ); + + // A + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); + A(IDX::X, IDX::YAW) = -X_t(IDX::VX) * sin_yaw * dt; + A(IDX::X, IDX::VX) = cos_yaw * dt; + A(IDX::Y, IDX::YAW) = X_t(IDX::VX) * cos_yaw * dt; + A(IDX::Y, IDX::VX) = sin_yaw * dt; + A(IDX::YAW, IDX::WZ) = dt; + + // Q + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + // Rotate the covariance matrix according to the vehicle yaw + // because q_cov_x and y are in the vehicle coordinate system. + Q(IDX::X, IDX::X) = + (ekf_params_.q_cov_x * cos_yaw * cos_yaw + ekf_params_.q_cov_y * sin_yaw * sin_yaw) * dt * dt; + Q(IDX::X, IDX::Y) = (0.5f * (ekf_params_.q_cov_x - ekf_params_.q_cov_y) * sin_2yaw) * dt * dt; + Q(IDX::Y, IDX::Y) = + (ekf_params_.q_cov_x * sin_yaw * sin_yaw + ekf_params_.q_cov_y * cos_yaw * cos_yaw) * dt * dt; + Q(IDX::Y, IDX::X) = Q(IDX::X, IDX::Y); + Q(IDX::YAW, IDX::YAW) = ekf_params_.q_cov_yaw * dt * dt; + Q(IDX::VX, IDX::VX) = ekf_params_.q_cov_vx * dt * dt; + Q(IDX::WZ, IDX::WZ) = ekf_params_.q_cov_wz * dt * dt; + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(ekf_params_.dim_x, 1); + + if (!ekf.predict(X_next_t, A, Q)) { + RCLCPP_WARN(logger_, "Cannot predict"); + } + + return true; +} + +bool NormalVehicleTracker::measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + + float r_cov_x; + float r_cov_y; + const uint8_t label = utils::getHighestProbLabel(object.classification); + + if (label == Label::CAR) { + r_cov_x = ekf_params_.r_cov_x; + r_cov_y = ekf_params_.r_cov_y; + } else if (label == Label::TRUCK || label == Label::BUS) { + constexpr float r_stddev_x = 8.0; // [m] + constexpr float r_stddev_y = 0.8; // [m] + r_cov_x = std::pow(r_stddev_x, 2.0); + r_cov_y = std::pow(r_stddev_y, 2.0); + } else { + r_cov_x = ekf_params_.r_cov_x; + r_cov_y = ekf_params_.r_cov_y; + } + + constexpr int dim_y = 3; // pos x, pos y, yaw, depending on Pose output + double measurement_yaw = autoware_utils::normalizeRadian( + tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + ekf_.getX(X_t); + // Fixed measurement_yaw to be in the range of +-90 degrees of X_t(IDX::YAW) + while (M_PI_2 <= X_t(IDX::YAW) - measurement_yaw) { + measurement_yaw = measurement_yaw + M_PI; + } + while (M_PI_2 <= measurement_yaw - X_t(IDX::YAW)) { + measurement_yaw = measurement_yaw - M_PI; + } + } + + /* Set measurement matrix */ + Eigen::MatrixXd Y(dim_y, 1); + Y << object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y, measurement_yaw; + + /* Set measurement matrix */ + Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, ekf_params_.dim_x); + C(0, IDX::X) = 1.0; // for pos x + C(1, IDX::Y) = 1.0; // for pos y + C(2, IDX::YAW) = 1.0; // for yaw + + /* Set measurement noise covariance */ + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] == 0.0) { + const double cos_yaw = std::cos(measurement_yaw); + const double sin_yaw = std::sin(measurement_yaw); + const double sin_2yaw = std::sin(2.0f * measurement_yaw); + R(0, 0) = r_cov_x * cos_yaw * cos_yaw + r_cov_y * sin_yaw * sin_yaw; // x - x + R(0, 1) = 0.5f * (r_cov_x - r_cov_y) * sin_2yaw; // x - y + R(1, 1) = r_cov_x * sin_yaw * sin_yaw + r_cov_y * cos_yaw * cos_yaw; // y - y + R(1, 0) = R(0, 1); // y - x + R(2, 2) = ekf_params_.r_cov_yaw; // yaw - yaw + } else { + R(0, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + R(0, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + R(0, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW]; + R(1, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + R(1, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + R(1, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_YAW]; + R(2, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X]; + R(2, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_Y]; + R(2, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } + if (!ekf_.update(Y, C, R)) { + RCLCPP_WARN(logger_, "Cannot update"); + } + + // normalize yaw and limit vx, wz + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + Eigen::MatrixXd P_t(ekf_params_.dim_x, ekf_params_.dim_x); + ekf_.getX(X_t); + ekf_.getP(P_t); + X_t(IDX::YAW) = autoware_utils::normalizeRadian(X_t(IDX::YAW)); + if (!(-max_vx_ <= X_t(IDX::VX) && X_t(IDX::VX) <= max_vx_)) { + X_t(IDX::VX) = X_t(IDX::VX) < 0 ? -max_vx_ : max_vx_; + } + if (!(-max_wz_ <= X_t(IDX::WZ) && X_t(IDX::WZ) <= max_wz_)) { + X_t(IDX::WZ) = X_t(IDX::WZ) < 0 ? -max_wz_ : max_wz_; + } + ekf_.init(X_t, P_t); + } + + // position z + constexpr float gain = 0.9; + z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; + + return true; +} + +bool NormalVehicleTracker::measureWithShape( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return false; + } + constexpr float gain = 0.9; + + bounding_box_.width = gain * bounding_box_.width + (1.0 - gain) * object.shape.dimensions.x; + bounding_box_.length = gain * bounding_box_.length + (1.0 - gain) * object.shape.dimensions.y; + bounding_box_.height = gain * bounding_box_.height + (1.0 - gain) * object.shape.dimensions.z; + + return true; +} + +bool NormalVehicleTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + object_ = object; + + if (0.01 /*10msec*/ < std::fabs((time - last_update_time_).seconds())) { + RCLCPP_WARN( + logger_, "There is a large gap between predicted time and measurement time. (%f)", + (time - last_update_time_).seconds()); + } + + measureWithPose(object); + measureWithShape(object); + + return true; +} + +bool NormalVehicleTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + object = utils::toTrackedObject(object_); + object.object_id = getUUID(); + object.classification = getClassification(); + + // predict kinematics + KalmanFilter tmp_ekf_for_no_update = ekf_; + const double dt = (time - last_update_time_).seconds(); + if (0.001 /*1msec*/ < dt) { + predict(dt, tmp_ekf_for_no_update); + } + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + Eigen::MatrixXd P(ekf_params_.dim_x, ekf_params_.dim_x); // predicted state + tmp_ekf_for_no_update.getX(X_t); + tmp_ekf_for_no_update.getP(P); + + // position + object.kinematics.pose_with_covariance.pose.position.x = X_t(IDX::X); + object.kinematics.pose_with_covariance.pose.position.y = X_t(IDX::Y); + object.kinematics.pose_with_covariance.pose.position.z = z_; + // quaternion + { + double roll, pitch, yaw; + tf2::Quaternion original_quaternion; + tf2::fromMsg(object_.kinematics.pose_with_covariance.pose.orientation, original_quaternion); + tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw); + tf2::Quaternion filtered_quaternion; + filtered_quaternion.setRPY(roll, pitch, X_t(IDX::YAW)); + object.kinematics.pose_with_covariance.pose.orientation.x = filtered_quaternion.x(); + object.kinematics.pose_with_covariance.pose.orientation.y = filtered_quaternion.y(); + object.kinematics.pose_with_covariance.pose.orientation.z = filtered_quaternion.z(); + object.kinematics.pose_with_covariance.pose.orientation.w = filtered_quaternion.w(); + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } + // position covariance + constexpr double z_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double r_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double p_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::X, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y] = P(IDX::X, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X] = P(IDX::Y, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = z_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = r_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = p_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::YAW, IDX::YAW); + + // twist + object.kinematics.twist_with_covariance.twist.linear.x = X_t(IDX::VX); + object.kinematics.twist_with_covariance.twist.angular.z = X_t(IDX::WZ); + // twist covariance + constexpr double vy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double vz_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wx_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::VX, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = vy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = vz_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW] = + P(IDX::VX, IDX::WZ); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X] = + P(IDX::WZ, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = wx_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = wy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::WZ, IDX::WZ); + + // set shape + object.shape.dimensions.x = bounding_box_.width; + object.shape.dimensions.y = bounding_box_.length; + object.shape.dimensions.z = bounding_box_.height; + + return true; +} diff --git a/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp new file mode 100644 index 0000000000000..74d1d254bdbb8 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp @@ -0,0 +1,61 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include "multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp" + +#include + +PedestrianAndBicycleTracker::PedestrianAndBicycleTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + pedestrian_tracker_(time, object), + bicycle_tracker_(time, object) +{ +} + +bool PedestrianAndBicycleTracker::predict(const rclcpp::Time & time) +{ + pedestrian_tracker_.predict(time); + bicycle_tracker_.predict(time); + return true; +} + +bool PedestrianAndBicycleTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + pedestrian_tracker_.measure(object, time); + bicycle_tracker_.measure(object, time); + setClassification(object.classification); + return true; +} + +bool PedestrianAndBicycleTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + const uint8_t label = getHighestProbLabel(); + + if (label == Label::PEDESTRIAN) { + pedestrian_tracker_.getTrackedObject(time, object); + } else if (label == Label::BICYCLE || label == Label::MOTORCYCLE) { + bicycle_tracker_.getTrackedObject(time, object); + } + object.object_id = getUUID(); + object.classification = getClassification(); + return true; +} diff --git a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp new file mode 100644 index 0000000000000..88bd5f44488c4 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp @@ -0,0 +1,409 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include "multi_object_tracker/tracker/model/pedestrian_tracker.hpp" + +#include "multi_object_tracker/utils/utils.hpp" + +#include + +#include +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include +#include + +PedestrianTracker::PedestrianTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + logger_(rclcpp::get_logger("PedestrianTracker")), + last_update_time_(time), + z_(object.kinematics.pose_with_covariance.pose.position.z) +{ + object_ = object; + + // initialize params + ekf_params_.use_measurement_covariance = false; + float q_stddev_x = 0.0; // [m/s] + float q_stddev_y = 0.0; // [m/s] + float q_stddev_yaw = autoware_utils::deg2rad(20); // [rad/s] + float q_stddev_vx = autoware_utils::kmph2mps(5); // [m/(s*s)] + float q_stddev_wz = autoware_utils::deg2rad(20); // [rad/(s*s)] + float r_stddev_x = 0.4; // [m] + float r_stddev_y = 0.4; // [m] + float r_stddev_yaw = autoware_utils::deg2rad(30); // [rad] + float p0_stddev_x = 1.0; // [m/s] + float p0_stddev_y = 1.0; // [m/s] + float p0_stddev_yaw = autoware_utils::deg2rad(1000); // [rad/s] + float p0_stddev_vx = autoware_utils::kmph2mps(5); // [m/(s*s)] + float p0_stddev_wz = autoware_utils::deg2rad(10); // [rad/(s*s)] + ekf_params_.q_cov_x = std::pow(q_stddev_x, 2.0); + ekf_params_.q_cov_y = std::pow(q_stddev_y, 2.0); + ekf_params_.q_cov_yaw = std::pow(q_stddev_yaw, 2.0); + ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); + ekf_params_.q_cov_wz = std::pow(q_stddev_wz, 2.0); + ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); + ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); + ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); + ekf_params_.p0_cov_x = std::pow(p0_stddev_x, 2.0); + ekf_params_.p0_cov_y = std::pow(p0_stddev_y, 2.0); + ekf_params_.p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + ekf_params_.p0_cov_vx = std::pow(p0_stddev_vx, 2.0); + ekf_params_.p0_cov_wz = std::pow(p0_stddev_wz, 2.0); + max_vx_ = autoware_utils::kmph2mps(10); // [m/s] + max_wz_ = autoware_utils::deg2rad(30); // [rad/s] + + // initialize X matrix + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + X(IDX::X) = object.kinematics.pose_with_covariance.pose.position.x; + X(IDX::Y) = object.kinematics.pose_with_covariance.pose.position.y; + X(IDX::YAW) = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + if (object.kinematics.has_twist) { + X(IDX::VX) = object.kinematics.twist_with_covariance.twist.linear.x; + X(IDX::WZ) = object.kinematics.twist_with_covariance.twist.angular.z; + } else { + X(IDX::VX) = 0.0; + X(IDX::WZ) = 0.0; + } + + // initialize P matrix + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] == 0.0) { + const double cos_yaw = std::cos(X(IDX::YAW)); + const double sin_yaw = std::sin(X(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X(IDX::YAW)); + // Rotate the covariance matrix according to the vehicle yaw + // because p0_cov_x and y are in the vehicle coordinate system. + P(IDX::X, IDX::X) = + ekf_params_.p0_cov_x * cos_yaw * cos_yaw + ekf_params_.p0_cov_y * sin_yaw * sin_yaw; + P(IDX::X, IDX::Y) = 0.5f * (ekf_params_.p0_cov_x - ekf_params_.p0_cov_y) * sin_2yaw; + P(IDX::Y, IDX::Y) = + ekf_params_.p0_cov_x * sin_yaw * sin_yaw + ekf_params_.p0_cov_y * cos_yaw * cos_yaw; + P(IDX::Y, IDX::X) = P(IDX::X, IDX::Y); + P(IDX::YAW, IDX::YAW) = ekf_params_.p0_cov_yaw; + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } else { + P(IDX::X, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::X, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + P(IDX::Y, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P(IDX::Y, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + P(IDX::YAW, IDX::YAW) = + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + if (object.kinematics.has_twist_covariance) { + P(IDX::VX, IDX::VX) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::WZ, IDX::WZ) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } else { + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + } + } + + bounding_box_ = {0.5, 0.5, 1.7}; + cylinder_ = {0.3, 1.7}; + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_ = { + object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + cylinder_ = {object.shape.dimensions.x, object.shape.dimensions.z}; + } + + ekf_.init(X, P); +} + +bool PedestrianTracker::predict(const rclcpp::Time & time) +{ + const double dt = (time - last_update_time_).seconds(); + bool ret = predict(dt, ekf_); + if (ret) { + last_update_time_ = time; + } + return ret; +} + +bool PedestrianTracker::predict(const double dt, KalmanFilter & ekf) const +{ + /* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * cos(yaw_k) * dt + * y_{k+1} = y_k + vx_k * sin(yaw_k) * dt + * yaw_{k+1} = yaw_k + (wz_k) * dt + * vx_{k+1} = vx_k + * wz_{k+1} = wz_k + * + */ + + /* == Linearized model == + * + * A = [ 1, 0, -vx*sin(yaw)*dt, cos(yaw)*dt, 0] + * [ 0, 1, vx*cos(yaw)*dt, sin(yaw)*dt, 0] + * [ 0, 0, 1, 0, dt] + * [ 0, 0, 0, 1, 0] + * [ 0, 0, 0, 0, 1] + */ + + // X t + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + ekf.getX(X_t); + const double cos_yaw = std::cos(X_t(IDX::YAW)); + const double sin_yaw = std::sin(X_t(IDX::YAW)); + const double sin_2yaw = std::sin(2.0f * X_t(IDX::YAW)); + + // X t+1 + Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); // predicted state + X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VX) * cos_yaw * dt; // dx = v * cos(yaw) + X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VX) * sin_yaw * dt; // dy = v * sin(yaw) + X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ)) * dt; // dyaw = omega + X_next_t(IDX::VX) = X_t(IDX::VX); + X_next_t(IDX::WZ) = X_t(IDX::WZ); + + // A + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); + A(IDX::X, IDX::YAW) = -X_t(IDX::VX) * sin_yaw * dt; + A(IDX::X, IDX::VX) = cos_yaw * dt; + A(IDX::Y, IDX::YAW) = X_t(IDX::VX) * cos_yaw * dt; + A(IDX::Y, IDX::VX) = sin_yaw * dt; + A(IDX::YAW, IDX::WZ) = dt; + + // Q + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + // Rotate the covariance matrix according to the vehicle yaw + // because q_cov_x and y are in the vehicle coordinate system. + Q(IDX::X, IDX::X) = + (ekf_params_.q_cov_x * cos_yaw * cos_yaw + ekf_params_.q_cov_y * sin_yaw * sin_yaw) * dt * dt; + Q(IDX::X, IDX::Y) = (0.5f * (ekf_params_.q_cov_x - ekf_params_.q_cov_y) * sin_2yaw) * dt * dt; + Q(IDX::Y, IDX::Y) = + (ekf_params_.q_cov_x * sin_yaw * sin_yaw + ekf_params_.q_cov_y * cos_yaw * cos_yaw) * dt * dt; + Q(IDX::Y, IDX::X) = Q(IDX::X, IDX::Y); + Q(IDX::YAW, IDX::YAW) = ekf_params_.q_cov_yaw * dt * dt; + Q(IDX::VX, IDX::VX) = ekf_params_.q_cov_vx * dt * dt; + Q(IDX::WZ, IDX::WZ) = ekf_params_.q_cov_wz * dt * dt; + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(ekf_params_.dim_x, 1); + + if (!ekf.predict(X_next_t, A, Q)) { + RCLCPP_WARN(logger_, "Cannot predict"); + } + + return true; +} + +bool PedestrianTracker::measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + constexpr int dim_y = 2; // pos x, pos y depending on Pose output + // double measurement_yaw = + // autoware_utils::normalizeRadian(tf2::getYaw(object.state.pose_covariance.pose.orientation)); + // { + // Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + // ekf_.getX(X_t); + // while (M_PI_2 <= X_t(IDX::YAW) - measurement_yaw) { + // measurement_yaw = measurement_yaw + M_PI; + // } + // while (M_PI_2 <= measurement_yaw - X_t(IDX::YAW)) { + // measurement_yaw = measurement_yaw - M_PI; + // } + // float theta = std::acos( + // std::cos(X_t(IDX::YAW)) * std::cos(measurement_yaw) + + // std::sin(X_t(IDX::YAW)) * std::sin(measurement_yaw)); + // if (autoware_utils::deg2rad(60) < std::fabs(theta)) return false; + // } + + /* Set measurement matrix */ + Eigen::MatrixXd Y(dim_y, 1); + Y << object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y; + + /* Set measurement matrix */ + Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, ekf_params_.dim_x); + C(0, IDX::X) = 1.0; // for pos x + C(1, IDX::Y) = 1.0; // for pos y + // C(2, IDX::YAW) = 1.0; // for yaw + + /* Set measurement noise covariance */ + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0) { + R(0, 0) = ekf_params_.r_cov_x; // x - x + R(0, 1) = 0.0; // x - y + R(1, 1) = ekf_params_.r_cov_y; // y - y + R(1, 0) = R(0, 1); // y - x + // R(2, 2) = ekf_params_.r_cov_yaw; // yaw - yaw + } else { + R(0, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + R(0, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + // R(0, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW]; + R(1, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + R(1, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + // R(1, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_YAW]; + // R(2, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X]; + // R(2, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_Y]; + // R(2, 2) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW]; + } + if (!ekf_.update(Y, C, R)) { + RCLCPP_WARN(logger_, "Cannot update"); + } + + // normalize yaw and limit vx, wz + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + Eigen::MatrixXd P_t(ekf_params_.dim_x, ekf_params_.dim_x); + ekf_.getX(X_t); + ekf_.getP(P_t); + X_t(IDX::YAW) = autoware_utils::normalizeRadian(X_t(IDX::YAW)); + if (!(-max_vx_ <= X_t(IDX::VX) && X_t(IDX::VX) <= max_vx_)) { + X_t(IDX::VX) = X_t(IDX::VX) < 0 ? -max_vx_ : max_vx_; + } + if (!(-max_wz_ <= X_t(IDX::WZ) && X_t(IDX::WZ) <= max_wz_)) { + X_t(IDX::WZ) = X_t(IDX::WZ) < 0 ? -max_wz_ : max_wz_; + } + ekf_.init(X_t, P_t); + } + + // position z + constexpr float gain = 0.9; + z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; + + return true; +} + +bool PedestrianTracker::measureWithShape( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + constexpr float gain = 0.9; + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_.width = gain * bounding_box_.width + (1.0 - gain) * object.shape.dimensions.x; + bounding_box_.length = gain * bounding_box_.length + (1.0 - gain) * object.shape.dimensions.y; + bounding_box_.height = gain * bounding_box_.height + (1.0 - gain) * object.shape.dimensions.z; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + cylinder_.width = gain * cylinder_.width + (1.0 - gain) * object.shape.dimensions.x; + cylinder_.height = gain * cylinder_.height + (1.0 - gain) * object.shape.dimensions.z; + } else { + return false; + } + + return true; +} + +bool PedestrianTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + object_ = object; + + if (0.01 /*10msec*/ < std::fabs((time - last_update_time_).seconds())) { + RCLCPP_WARN( + logger_, "There is a large gap between predicted time and measurement time. (%f)", + (time - last_update_time_).seconds()); + } + + measureWithPose(object); + measureWithShape(object); + + return true; +} + +bool PedestrianTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + object = utils::toTrackedObject(object_); + object.object_id = getUUID(); + object.classification = getClassification(); + + // predict kinematics + KalmanFilter tmp_ekf_for_no_update = ekf_; + const double dt = (time - last_update_time_).seconds(); + if (0.001 /*1msec*/ < dt) { + predict(dt, tmp_ekf_for_no_update); + } + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + Eigen::MatrixXd P(ekf_params_.dim_x, ekf_params_.dim_x); // predicted state + tmp_ekf_for_no_update.getX(X_t); + tmp_ekf_for_no_update.getP(P); + + // position + object.kinematics.pose_with_covariance.pose.position.x = X_t(IDX::X); + object.kinematics.pose_with_covariance.pose.position.y = X_t(IDX::Y); + object.kinematics.pose_with_covariance.pose.position.z = z_; + // quaternion + { + double roll, pitch, yaw; + tf2::Quaternion original_quaternion; + tf2::fromMsg(object_.kinematics.pose_with_covariance.pose.orientation, original_quaternion); + tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw); + tf2::Quaternion filtered_quaternion; + filtered_quaternion.setRPY(roll, pitch, X_t(IDX::YAW)); + object.kinematics.pose_with_covariance.pose.orientation.x = filtered_quaternion.x(); + object.kinematics.pose_with_covariance.pose.orientation.y = filtered_quaternion.y(); + object.kinematics.pose_with_covariance.pose.orientation.z = filtered_quaternion.z(); + object.kinematics.pose_with_covariance.pose.orientation.w = filtered_quaternion.w(); + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } + // position covariance + constexpr double z_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double r_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double p_cov = 0.1 * 0.1; // TOTODO(yukkysaito)DO Currently tentative + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::X, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y] = P(IDX::X, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X] = P(IDX::Y, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = z_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = r_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = p_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::YAW, IDX::YAW); + + // twist + object.kinematics.twist_with_covariance.twist.linear.x = X_t(IDX::VX); + object.kinematics.twist_with_covariance.twist.angular.z = X_t(IDX::WZ); + // twist covariance + constexpr double vy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double vz_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wx_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::VX, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = vy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = vz_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_YAW] = + P(IDX::VX, IDX::WZ); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_X] = + P(IDX::WZ, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = wx_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = wy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = + P(IDX::WZ, IDX::WZ); + + // set shape + object.shape.dimensions.x = bounding_box_.width; + object.shape.dimensions.y = bounding_box_.length; + object.shape.dimensions.z = bounding_box_.height; + + return true; +} diff --git a/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp b/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp new file mode 100644 index 0000000000000..82db76d9901e2 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp @@ -0,0 +1,63 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include + +Tracker::Tracker( + const rclcpp::Time & time, + const std::vector & classification) +: classification_(classification), + no_measurement_count_(0), + total_no_measurement_count_(0), + total_measurement_count_(1), + last_update_with_measurement_time_(time) +{ + // Generate random number + std::mt19937 gen(std::random_device{}()); + std::independent_bits_engine bit_eng(gen); + std::generate(uuid_.uuid.begin(), uuid_.uuid.end(), bit_eng); +} + +bool Tracker::updateWithMeasurement( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const rclcpp::Time & measurement_time) +{ + no_measurement_count_ = 0; + ++total_measurement_count_; + last_update_with_measurement_time_ = measurement_time; + measure(object, measurement_time); + return true; +} + +bool Tracker::updateWithoutMeasurement() +{ + ++no_measurement_count_; + ++total_no_measurement_count_; + return true; +} + +geometry_msgs::msg::PoseWithCovariance Tracker::getPoseWithCovariance( + const rclcpp::Time & time) const +{ + autoware_auto_perception_msgs::msg::TrackedObject object; + getTrackedObject(time, object); + return object.kinematics.pose_with_covariance; +} diff --git a/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp new file mode 100644 index 0000000000000..ebc484b84ef76 --- /dev/null +++ b/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp @@ -0,0 +1,298 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include +#define EIGEN_MPL2_ONLY +#include "multi_object_tracker/tracker/model/unknown_tracker.hpp" +#include "multi_object_tracker/utils/utils.hpp" + +#include +#include +#include + +UnknownTracker::UnknownTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object) +: Tracker(time, object.classification), + logger_(rclcpp::get_logger("UnknownTracker")), + last_update_time_(time), + z_(object.kinematics.pose_with_covariance.pose.position.z) +{ + object_ = object; + + // initialize params + ekf_params_.use_measurement_covariance = false; + float q_stddev_x = 0.0; // [m/s] + float q_stddev_y = 0.0; // [m/s] + float q_stddev_vx = autoware_utils::kmph2mps(0.1); // [m/(s*s)] + float q_stddev_vy = autoware_utils::kmph2mps(0.1); // [m/(s*s)] + float r_stddev_x = 0.4; // [m] + float r_stddev_y = 0.4; // [m] + float p0_stddev_x = 1.0; // [m/s] + float p0_stddev_y = 1.0; // [m/s] + float p0_stddev_vx = autoware_utils::kmph2mps(0.1); // [m/(s*s)] + float p0_stddev_vy = autoware_utils::kmph2mps(0.1); // [m/(s*s)] + ekf_params_.q_cov_x = std::pow(q_stddev_x, 2.0); + ekf_params_.q_cov_y = std::pow(q_stddev_y, 2.0); + ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); + ekf_params_.q_cov_vy = std::pow(q_stddev_vy, 2.0); + ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); + ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); + ekf_params_.p0_cov_x = std::pow(p0_stddev_x, 2.0); + ekf_params_.p0_cov_y = std::pow(p0_stddev_y, 2.0); + ekf_params_.p0_cov_vx = std::pow(p0_stddev_vx, 2.0); + ekf_params_.p0_cov_vy = std::pow(p0_stddev_vy, 2.0); + max_vx_ = autoware_utils::kmph2mps(5); // [m/s] + max_vy_ = autoware_utils::kmph2mps(5); // [m/s] + + // initialize X matrix + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + X(IDX::X) = object.kinematics.pose_with_covariance.pose.position.x; + X(IDX::Y) = object.kinematics.pose_with_covariance.pose.position.y; + if (object.kinematics.has_twist) { + X(IDX::VX) = object.kinematics.twist_with_covariance.twist.linear.x; + X(IDX::VY) = object.kinematics.twist_with_covariance.twist.linear.y; + } else { + X(IDX::VX) = 0.0; + X(IDX::VY) = 0.0; + } + + // initialize P matrix + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0) { + // Rotate the covariance matrix according to the vehicle yaw + // because p0_cov_x and y are in the vehicle coordinate system. + P(IDX::X, IDX::X) = ekf_params_.p0_cov_x; + P(IDX::X, IDX::Y) = 0.0; + P(IDX::Y, IDX::Y) = ekf_params_.p0_cov_y; + P(IDX::Y, IDX::X) = P(IDX::X, IDX::Y); + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::VY, IDX::VY) = ekf_params_.p0_cov_vy; + } else { + P(IDX::X, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::X, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + P(IDX::Y, IDX::Y) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P(IDX::Y, IDX::X) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + if (object.kinematics.has_twist_covariance) { + P(IDX::VX, IDX::VX) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + P(IDX::VY, IDX::VY) = + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + } else { + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + P(IDX::VY, IDX::VY) = ekf_params_.p0_cov_vy; + } + } + + ekf_.init(X, P); +} + +bool UnknownTracker::predict(const rclcpp::Time & time) +{ + const double dt = (time - last_update_time_).seconds(); + bool ret = predict(dt, ekf_); + if (ret) { + last_update_time_ = time; + } + return ret; +} + +bool UnknownTracker::predict(const double dt, KalmanFilter & ekf) const +{ + /* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * dt + * y_{k+1} = y_k + vx_k * dt + * vx_{k+1} = vx_k + * vy_{k+1} = vy_k + * + */ + + /* == Linearized model == + * + * A = [ 1, 0, dt, 0] + * [ 0, 1, 0, dt] + * [ 0, 0, 1, 0] + * [ 0, 0, 0, 1] + */ + + // X t + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + ekf.getX(X_t); + + // X t+1 + Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); // predicted state + X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VX) * dt; + X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VY) * dt; + X_next_t(IDX::VX) = X_t(IDX::VX); + X_next_t(IDX::VY) = X_t(IDX::VY); + + // A + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); + A(IDX::X, IDX::VX) = dt; + A(IDX::Y, IDX::VY) = dt; + + // Q + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + // Rotate the covariance matrix according to the vehicle yaw + // because q_cov_x and y are in the vehicle coordinate system. + Q(IDX::X, IDX::X) = ekf_params_.q_cov_x * dt * dt; + Q(IDX::X, IDX::Y) = 0.0; + Q(IDX::Y, IDX::Y) = ekf_params_.q_cov_y * dt * dt; + Q(IDX::Y, IDX::X) = Q(IDX::X, IDX::Y); + Q(IDX::VX, IDX::VX) = ekf_params_.q_cov_vx * dt * dt; + Q(IDX::VY, IDX::VY) = ekf_params_.q_cov_vy * dt * dt; + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(ekf_params_.dim_x, 1); + + if (!ekf.predict(X_next_t, A, Q)) { + RCLCPP_WARN(logger_, "Pedestrian : Cannot predict"); + } + + return true; +} + +bool UnknownTracker::measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + constexpr int dim_y = 2; // pos x, pos y depending on Pose output + + /* Set measurement matrix */ + Eigen::MatrixXd Y(dim_y, 1); + Y << object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y; + + /* Set measurement matrix */ + Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, ekf_params_.dim_x); + C(0, IDX::X) = 1.0; // for pos x + C(1, IDX::Y) = 1.0; // for pos y + + /* Set measurement noise covariance */ + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); + if ( + !ekf_params_.use_measurement_covariance || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] == 0.0 || + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] == 0.0) { + R(0, 0) = ekf_params_.r_cov_x; // x - x + R(0, 1) = 0.0; // x - y + R(1, 1) = ekf_params_.r_cov_y; // y - y + R(1, 0) = R(0, 1); // y - x + } else { + R(0, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + R(0, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y]; + R(1, 0) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X]; + R(1, 1) = object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + } + if (!ekf_.update(Y, C, R)) { + RCLCPP_WARN(logger_, "Pedestrian : Cannot update"); + } + + // limit vx, vy + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + Eigen::MatrixXd P_t(ekf_params_.dim_x, ekf_params_.dim_x); + ekf_.getX(X_t); + ekf_.getP(P_t); + if (!(-max_vx_ <= X_t(IDX::VX) && X_t(IDX::VX) <= max_vx_)) { + X_t(IDX::VX) = X_t(IDX::VX) < 0 ? -max_vx_ : max_vx_; + } + if (!(-max_vy_ <= X_t(IDX::VY) && X_t(IDX::VY) <= max_vy_)) { + X_t(IDX::VY) = X_t(IDX::VY) < 0 ? -max_vy_ : max_vy_; + } + ekf_.init(X_t, P_t); + } + + // position z + constexpr float gain = 0.9; + z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; + + return true; +} + +bool UnknownTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time) +{ + object_ = object; + + if (0.01 /*10msec*/ < std::fabs((time - last_update_time_).seconds())) { + RCLCPP_WARN( + logger_, + "Pedestrian : There is a large gap between predicted time and measurement time. (%f)", + (time - last_update_time_).seconds()); + } + + measureWithPose(object); + + return true; +} + +bool UnknownTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + object = utils::toTrackedObject(object_); + object.object_id = getUUID(); + object.classification = getClassification(); + + // predict kinematics + KalmanFilter tmp_ekf_for_no_update = ekf_; + const double dt = (time - last_update_time_).seconds(); + if (0.001 /*1msec*/ < dt) { + predict(dt, tmp_ekf_for_no_update); + } + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + Eigen::MatrixXd P(ekf_params_.dim_x, ekf_params_.dim_x); // predicted state + tmp_ekf_for_no_update.getX(X_t); + tmp_ekf_for_no_update.getP(P); + + // position + object.kinematics.pose_with_covariance.pose.position.x = X_t(IDX::X); + object.kinematics.pose_with_covariance.pose.position.y = X_t(IDX::Y); + object.kinematics.pose_with_covariance.pose.position.z = z_; + // position covariance + constexpr double z_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double r_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double p_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double yaw_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::X, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y] = P(IDX::X, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X] = P(IDX::Y, IDX::X); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = z_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = r_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = p_cov; + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = yaw_cov; + + // twist + object.kinematics.twist_with_covariance.twist.linear.x = X_t(IDX::VX); + object.kinematics.twist_with_covariance.twist.linear.y = X_t(IDX::VY); + // twist covariance + constexpr double vz_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wx_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wy_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + constexpr double wz_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::VX, IDX::VX); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y] = P(IDX::VY, IDX::VY); + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Z_Z] = vz_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = wx_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = wy_cov; + object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::YAW_YAW] = wz_cov; + + return true; +} diff --git a/perception/multi_object_tracker/src/utils/utils.cpp b/perception/multi_object_tracker/src/utils/utils.cpp new file mode 100644 index 0000000000000..723262f551136 --- /dev/null +++ b/perception/multi_object_tracker/src/utils/utils.cpp @@ -0,0 +1,218 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include "multi_object_tracker/utils/utils.hpp" + +#include + +#include +#include + +#include +#include + +namespace utils +{ +void toPolygon2d( + const autoware_auto_perception_msgs::msg::TrackedObject & object, + autoware_utils::Polygon2d & output); +bool isClockWise(const autoware_utils::Polygon2d & polygon); +autoware_utils::Polygon2d inverseClockWise(const autoware_utils::Polygon2d & polygon); + +double getArea(const autoware_auto_perception_msgs::msg::Shape & shape) +{ + double area = 0.0; + if (shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + area = getRectangleArea(shape.dimensions); + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + area = getCircleArea(shape.dimensions); + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + area = getPolygonArea(shape.footprint); + } + return area; +} + +double getPolygonArea(const geometry_msgs::msg::Polygon & footprint) +{ + double area = 0.0; + + for (int i = 0; i < static_cast(footprint.points.size()); ++i) { + int j = (i + 1) % static_cast(footprint.points.size()); + area += 0.5 * (footprint.points.at(i).x * footprint.points.at(j).y - + footprint.points.at(j).x * footprint.points.at(i).y); + } + + return area; +} + +double getRectangleArea(const geometry_msgs::msg::Vector3 & dimensions) +{ + return static_cast(dimensions.x * dimensions.y); +} + +double getCircleArea(const geometry_msgs::msg::Vector3 & dimensions) +{ + return static_cast((dimensions.x / 2.0) * (dimensions.x / 2.0) * M_PI); +} + +double get2dIoU( + const autoware_auto_perception_msgs::msg::TrackedObject & object1, + const autoware_auto_perception_msgs::msg::TrackedObject & object2) +{ + autoware_utils::Polygon2d polygon1, polygon2; + toPolygon2d(object1, polygon1); + toPolygon2d(object2, polygon2); + + std::vector union_polygons; + std::vector intersection_polygons; + boost::geometry::union_(polygon1, polygon2, union_polygons); + boost::geometry::intersection(polygon1, polygon2, intersection_polygons); + + double union_area = 0.0; + double intersection_area = 0.0; + for (const auto & union_polygon : union_polygons) { + union_area += boost::geometry::area(union_polygon); + } + for (const auto & intersection_polygon : intersection_polygons) { + intersection_area += boost::geometry::area(intersection_polygon); + } + double iou; + if (union_area < 0.01) { + iou = 0.0f; + } + iou = std::min(1.0, intersection_area / union_area); + return iou; +} + +autoware_utils::Polygon2d inverseClockWise(const autoware_utils::Polygon2d & polygon) +{ + autoware_utils::Polygon2d inverted_polygon; + for (int i = polygon.outer().size() - 1; 0 <= i; --i) { + inverted_polygon.outer().push_back(polygon.outer().at(i)); + } + return inverted_polygon; +} + +bool isClockWise(const autoware_utils::Polygon2d & polygon) +{ + const int n = polygon.outer().size(); + const double x_offset = polygon.outer().at(0).x(); + const double y_offset = polygon.outer().at(0).y(); + double sum = 0.0; + for (std::size_t i = 0; i < polygon.outer().size(); ++i) { + sum += + (polygon.outer().at(i).x() - x_offset) * (polygon.outer().at((i + 1) % n).y() - y_offset) - + (polygon.outer().at(i).y() - y_offset) * (polygon.outer().at((i + 1) % n).x() - x_offset); + } + + return sum < 0.0; +} + +void toPolygon2d( + const autoware_auto_perception_msgs::msg::TrackedObject & object, + autoware_utils::Polygon2d & output) +{ + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + const auto & pose = object.kinematics.pose_with_covariance.pose; + double yaw = autoware_utils::normalizeRadian(tf2::getYaw(pose.orientation)); + Eigen::Matrix2d rotation; + rotation << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw); + Eigen::Vector2d offset0, offset1, offset2, offset3; + offset0 = rotation * + Eigen::Vector2d(object.shape.dimensions.x * 0.5f, object.shape.dimensions.y * 0.5f); + offset1 = rotation * + Eigen::Vector2d(object.shape.dimensions.x * 0.5f, -object.shape.dimensions.y * 0.5f); + offset2 = rotation * + Eigen::Vector2d(-object.shape.dimensions.x * 0.5f, -object.shape.dimensions.y * 0.5f); + offset3 = rotation * + Eigen::Vector2d(-object.shape.dimensions.x * 0.5f, object.shape.dimensions.y * 0.5f); + output.outer().push_back(boost::geometry::make( + pose.position.x + offset0.x(), pose.position.y + offset0.y())); + output.outer().push_back(boost::geometry::make( + pose.position.x + offset1.x(), pose.position.y + offset1.y())); + output.outer().push_back(boost::geometry::make( + pose.position.x + offset2.x(), pose.position.y + offset2.y())); + output.outer().push_back(boost::geometry::make( + pose.position.x + offset3.x(), pose.position.y + offset3.y())); + output.outer().push_back(output.outer().front()); + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + const auto & center = object.kinematics.pose_with_covariance.pose.position; + const auto & radius = object.shape.dimensions.x * 0.5; + constexpr int n = 6; + for (int i = 0; i < n; ++i) { + Eigen::Vector2d point; + point.x() = std::cos( + (static_cast(i) / static_cast(n)) * 2.0 * M_PI + + M_PI / static_cast(n)) * + radius + + center.x; + point.y() = std::sin( + (static_cast(i) / static_cast(n)) * 2.0 * M_PI + + M_PI / static_cast(n)) * + radius + + center.y; + output.outer().push_back( + boost::geometry::make(point.x(), point.y())); + } + output.outer().push_back(output.outer().front()); + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + const auto & pose = object.kinematics.pose_with_covariance.pose; + // don't use yaw + // double yaw = autoware_utils::normalizeRadian(tf2::getYaw(pose.orientation)); + // Eigen::Matrix2d rotation; + // rotation << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw); + for (const auto & point : object.shape.footprint.points) { + output.outer().push_back(boost::geometry::make( + pose.position.x + point.x, pose.position.y + point.y)); + } + output.outer().push_back(output.outer().front()); + } + output = isClockWise(output) ? output : inverseClockWise(output); +} + +std::uint8_t getHighestProbLabel( + const std::vector & classification) +{ + std::uint8_t label = autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; + float highest_prob = 0.0; + for (const auto & _class : classification) { + if (highest_prob < _class.probability) { + highest_prob = _class.probability; + label = _class.label; + } + } + return label; +} + +autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject( + const autoware_auto_perception_msgs::msg::DetectedObject & detected_object) +{ + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + tracked_object.existence_probability = detected_object.existence_probability; + + tracked_object.classification = detected_object.classification; + + tracked_object.kinematics.pose_with_covariance = detected_object.kinematics.pose_with_covariance; + tracked_object.kinematics.twist_with_covariance = + detected_object.kinematics.twist_with_covariance; + + tracked_object.shape = detected_object.shape; + return tracked_object; +} + +} // namespace utils