From 1c86e7935d298285fb4417f05c093d057e7ec433 Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Sat, 8 Feb 2025 21:37:27 +0800 Subject: [PATCH 01/21] feat: migrate rviz to rviz2 --- rviz_cfg/fast_livo2.rviz | 84 ++++++++++++++++++++-------------------- 1 file changed, 42 insertions(+), 42 deletions(-) diff --git a/rviz_cfg/fast_livo2.rviz b/rviz_cfg/fast_livo2.rviz index da2892e3..9b69e325 100755 --- a/rviz_cfg/fast_livo2.rviz +++ b/rviz_cfg/fast_livo2.rviz @@ -1,5 +1,5 @@ Panels: - - Class: rviz/Displays + - Class: rviz_common/Displays Help Height: 0 Name: Displays Property Tree Widget: @@ -25,21 +25,21 @@ Panels: - /Image1 Splitter Ratio: 0.34272301197052 Tree Height: 538 - - Class: rviz/Selection + - Class: rviz_common/Selection Name: Selection - - Class: rviz/Tool Properties + - Class: rviz_common/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views + - Class: rviz_common/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: rviz/Time + - Class: rviz_common/Time Name: Time SyncMode: 0 SyncSource: surround @@ -52,7 +52,7 @@ Visualization Manager: Displays: - Alpha: 1 Cell Size: 1 - Class: rviz/Grid + Class: rviz_default_plugins/Grid Color: 160; 160; 164 Enabled: false Line Style: @@ -69,7 +69,7 @@ Visualization Manager: Reference Frame: Value: false - Alpha: 1 - Class: rviz/Axes + Class: rviz_default_plugins/Axes Enabled: true Length: 0.699999988079071 Name: Axes @@ -77,7 +77,7 @@ Visualization Manager: Reference Frame: Show Trail: false Value: true - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Alpha: 1 Autocompute Intensity Bounds: true @@ -87,7 +87,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: FlatColor Decay Time: 0 @@ -115,7 +115,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 238; 238; 236 Color Transformer: RGB8 Decay Time: 10000 @@ -145,7 +145,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: "" Decay Time: 0 @@ -167,10 +167,10 @@ Visualization Manager: Value: false Enabled: true Name: mapping - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Angle Tolerance: 0.009999999776482582 - Class: rviz/Odometry + Class: rviz_default_plugins/Odometry Covariance: Orientation: Alpha: 0.5 @@ -208,7 +208,7 @@ Visualization Manager: Name: Odometry - Alpha: 0 Buffer Length: 2 - Class: rviz/Path + Class: rviz_default_plugins/Path Color: 25; 255; 255 Enabled: true Head Diameter: 0 @@ -238,7 +238,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: Intensity Decay Time: 1000 @@ -258,7 +258,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: false - - Class: rviz/Marker + - Class: rviz_default_plugins/Marker Enabled: true Marker Topic: /planner_normal Name: Marker @@ -266,7 +266,7 @@ Visualization Manager: {} Queue Size: 100 Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /voxels Name: MarkerArray @@ -282,7 +282,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 245; 121; 0 Color Transformer: FlatColor Decay Time: 0 @@ -302,7 +302,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /visualization_marker Name: MarkerArray @@ -318,7 +318,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 92; 53; 102 Color Transformer: FlatColor Decay Time: 99999 @@ -346,7 +346,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 115; 210; 22 Color Transformer: FlatColor Decay Time: 0 @@ -374,7 +374,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 237; 212; 0 Color Transformer: FlatColor Decay Time: 0 @@ -402,7 +402,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: FlatColor Decay Time: 99999 @@ -430,7 +430,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 92; 53; 102 Color Transformer: FlatColor Decay Time: 0 @@ -451,7 +451,7 @@ Visualization Manager: Use rainbow: true Value: false - Angle Tolerance: 0 - Class: rviz/Odometry + Class: rviz_default_plugins/Odometry Covariance: Orientation: Alpha: 0.5 @@ -485,7 +485,7 @@ Visualization Manager: Topic: /aft_mapped_to_init Unreliable: false Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /waypoint_planner/visualize Name: MarkerArray @@ -493,7 +493,7 @@ Visualization Manager: {} Queue Size: 100 Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true Marker Topic: /fsm_node/visualization/exp_traj Name: MarkerArray @@ -501,7 +501,7 @@ Visualization Manager: {} Queue Size: 100 Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /fsm_node/visualization/exp_sfcs Name: MarkerArray @@ -509,7 +509,7 @@ Visualization Manager: {} Queue Size: 100 Value: false - - Class: rviz/Image + - Class: rviz_default_plugins/Image Enabled: true Image Topic: /rgb_img Max Value: 1 @@ -529,26 +529,26 @@ Visualization Manager: Frame Rate: 30 Name: root Tools: - - Class: rviz/Interact + - Class: rviz_default_plugins/Interact Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + - Class: rviz_default_plugins/SetInitialPose Theta std deviation: 0.2617993950843811 Topic: /initialpose X std deviation: 0.5 Y std deviation: 0.5 - - Class: rviz/SetGoal + - Class: rviz_default_plugins/SetGoal Topic: /move_base_simple/goal - - Class: rviz/PublishPoint + - Class: rviz_default_plugins/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: - Class: rviz/ThirdPersonFollower + Class: rviz_default_plugins/ThirdPersonFollower Distance: 25.669620513916016 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -569,7 +569,7 @@ Visualization Manager: Target Frame: drone Yaw: 3.161787748336792 Saved: - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 117.53474426269531 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -589,7 +589,7 @@ Visualization Manager: Pitch: 0.19539840519428253 Target Frame: Yaw: 0.17540442943572998 - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 109.3125 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -609,7 +609,7 @@ Visualization Manager: Pitch: 0.035398442298173904 Target Frame: Yaw: 5.793589115142822 - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 85.65605163574219 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -629,7 +629,7 @@ Visualization Manager: Pitch: 0.5653983950614929 Target Frame: Yaw: 0.9104044437408447 - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 60.1053581237793 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 From 374ab595483bd72a488c1fc1cf050505160a83c2 Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Mon, 10 Feb 2025 00:13:06 +0800 Subject: [PATCH 02/21] feat: migrate param loading from *.yaml --- config/avia.yaml | 150 +++++++++++++++++++------------------ config/camera_pinhole.yaml | 26 ++++--- 2 files changed, 90 insertions(+), 86 deletions(-) diff --git a/config/avia.yaml b/config/avia.yaml index 04c24bab..9eb6b085 100755 --- a/config/avia.yaml +++ b/config/avia.yaml @@ -1,85 +1,87 @@ -common: - img_topic: "/left_camera/image" - lid_topic: "/livox/lidar" - imu_topic: "/livox/imu" - img_en: 1 - lidar_en: 1 - ros_driver_bug_fix: false +/**: + ros__parameters: + common: + img_topic: "/left_camera/image" + lid_topic: "/livox/lidar" + imu_topic: "/livox/imu" + img_en: 1 + lidar_en: 1 + ros_driver_bug_fix: false -extrin_calib: - extrinsic_T: [0.04165, 0.02326, -0.0284] - extrinsic_R: [1, 0, 0, 0, 1, 0, 0, 0, 1] - Rcl: [0.00610193,-0.999863,-0.0154172, - -0.00615449,0.0153796,-0.999863, - 0.999962,0.00619598,-0.0060598] - Pcl: [0.0194384, 0.104689,-0.0251952] + extrin_calib: + extrinsic_T: [0.04165, 0.02326, -0.0284] + extrinsic_R: [1, 0, 0, 0, 1, 0, 0, 0, 1] + Rcl: [0.00610193,-0.999863,-0.0154172, + -0.00615449,0.0153796,-0.999863, + 0.999962,0.00619598,-0.0060598] + Pcl: [0.0194384, 0.104689,-0.0251952] -time_offset: - imu_time_offset: 0.0 - img_time_offset: 0.1 - exposure_time_init: 0.0 + time_offset: + imu_time_offset: 0.0 + img_time_offset: 0.1 + exposure_time_init: 0.0 -preprocess: - point_filter_num: 1 - filter_size_surf: 0.1 - lidar_type: 1 # Livox Avia LiDAR - scan_line: 6 - blind: 0.8 + preprocess: + point_filter_num: 1 + filter_size_surf: 0.1 + lidar_type: 1 # Livox Avia LiDAR + scan_line: 6 + blind: 0.8 -vio: - max_iterations: 5 - outlier_threshold: 1000 # 78 100 156 #100 200 500 700 infinite - img_point_cov: 100 # 100 1000 - patch_size: 8 - patch_pyrimid_level: 4 - normal_en: true - raycast_en: false - inverse_composition_en: false - exposure_estimate_en: true - inv_expo_cov: 0.1 + vio: + max_iterations: 5 + outlier_threshold: 1000 # 78 100 156 #100 200 500 700 infinite + img_point_cov: 100 # 100 1000 + patch_size: 8 + patch_pyrimid_level: 4 + normal_en: true + raycast_en: false + inverse_composition_en: false + exposure_estimate_en: true + inv_expo_cov: 0.1 -imu: - imu_en: true - imu_int_frame: 30 - acc_cov: 0.5 # 0.2 - gyr_cov: 0.3 # 0.5 - b_acc_cov: 0.0001 # 0.1 - b_gyr_cov: 0.0001 # 0.1 + imu: + imu_en: true + imu_int_frame: 30 + acc_cov: 0.5 # 0.2 + gyr_cov: 0.3 # 0.5 + b_acc_cov: 0.0001 # 0.1 + b_gyr_cov: 0.0001 # 0.1 -lio: - max_iterations: 5 - dept_err: 0.02 - beam_err: 0.05 - min_eigen_value: 0.0025 # 0.005 - voxel_size: 0.5 - max_layer: 2 - max_points_num: 50 - layer_init_num: [5, 5, 5, 5, 5] + lio: + max_iterations: 5 + dept_err: 0.02 + beam_err: 0.05 + min_eigen_value: 0.0025 # 0.005 + voxel_size: 0.5 + max_layer: 2 + max_points_num: 50 + layer_init_num: [5, 5, 5, 5, 5] -local_map: - map_sliding_en: false - half_map_size: 100 - sliding_thresh: 8 + local_map: + map_sliding_en: false + half_map_size: 100 + sliding_thresh: 8 -uav: - imu_rate_odom: false - gravity_align_en: false + uav: + imu_rate_odom: false + gravity_align_en: false -publish: - dense_map_en: true - pub_effect_point_en: false - pub_plane_en: false - pub_scan_num: 1 - blind_rgb_points: 0.0 + publish: + dense_map_en: true + pub_effect_point_en: false + pub_plane_en: false + pub_scan_num: 1 + blind_rgb_points: 0.0 -evo: - seq_name: "CBD_Building_01" - pose_output_en: false + evo: + seq_name: "CBD_Building_01" + pose_output_en: false -pcd_save: - pcd_save_en: false - colmap_output_en: false # need to set interval = -1 - filter_size_pcd: 0.15 - interval: -1 - # how many LiDAR frames saved in each pcd file; - # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. + pcd_save: + pcd_save_en: false + colmap_output_en: false # need to set interval = -1 + filter_size_pcd: 0.15 + interval: -1 + # how many LiDAR frames saved in each pcd file; + # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. diff --git a/config/camera_pinhole.yaml b/config/camera_pinhole.yaml index 83fd89e0..8c8da9a1 100644 --- a/config/camera_pinhole.yaml +++ b/config/camera_pinhole.yaml @@ -1,12 +1,14 @@ -cam_model: Pinhole -cam_width: 1280 -cam_height: 1024 -scale: 0.5 -cam_fx: 1293.56944 -cam_fy: 1293.3155 -cam_cx: 626.91359 -cam_cy: 522.799224 -cam_d0: -0.076160 -cam_d1: 0.123001 -cam_d2: -0.00113 -cam_d3: 0.000251 \ No newline at end of file +/**: + ros__parameters: + cam_model: Pinhole + cam_width: 1280 + cam_height: 1024 + scale: 0.5 + cam_fx: 1293.56944 + cam_fy: 1293.3155 + cam_cx: 626.91359 + cam_cy: 522.799224 + cam_d0: -0.076160 + cam_d1: 0.123001 + cam_d2: -0.00113 + cam_d3: 0.000251 \ No newline at end of file From 14cb3bc8f4745d31e25b5855c048476d8f7ea53a Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Sun, 23 Feb 2025 21:52:04 +0800 Subject: [PATCH 03/21] feat: migrate code from ros1 to ros2 --- CMakeLists.txt | 123 +++++++--- include/IMU_Processing.h | 7 +- include/LIVMapper.h | 93 ++++---- include/common_lib.h | 13 +- include/feature.h | 4 +- include/frame.h | 4 +- include/preprocess.h | 26 ++- include/utils/utils.h | 76 +++++++ include/vio.h | 8 +- include/voxel_map.h | 18 +- launch/mapping_avia.launch | 20 -- package.xml | 51 +++-- src/IMU_Processing.cpp | 48 ++-- src/LIVMapper.cpp | 446 +++++++++++++++++++++---------------- src/frame.cpp | 2 +- src/main.cpp | 14 +- src/preprocess.cpp | 24 +- src/utils.cpp | 19 ++ src/vio.cpp | 25 ++- src/voxel_map.cpp | 76 ++++--- 20 files changed, 665 insertions(+), 432 deletions(-) create mode 100644 include/utils/utils.h delete mode 100755 launch/mapping_avia.launch create mode 100644 src/utils.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f51009e..baac76bf 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.10) project(fast_livo) set(CMAKE_BUILD_TYPE "Release") @@ -75,57 +75,93 @@ else() message(STATUS "mimalloc not found, proceeding without it") endif() -# Find catkin and required dependencies -find_package(catkin REQUIRED COMPONENTS - geometry_msgs - nav_msgs - sensor_msgs - roscpp - rospy - std_msgs - pcl_ros - tf - livox_ros_driver - message_generation - eigen_conversions - vikit_common - vikit_ros - cv_bridge - image_transport -) - +# Find ament and required dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclpy REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(visualization_msgs REQUIRED) +find_package(pcl_ros REQUIRED) +find_package(pcl_conversions REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(livox_ros_driver2 REQUIRED) +find_package(vikit_common REQUIRED) +find_package(vikit_ros REQUIRED) +find_package(cv_bridge REQUIRED) +find_package(image_transport REQUIRED) find_package(Eigen3 REQUIRED) find_package(PCL REQUIRED) find_package(OpenCV REQUIRED) find_package(Sophus REQUIRED) find_package(Boost REQUIRED COMPONENTS thread) -# Define the catkin package -catkin_package( - CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs message_runtime cv_bridge vikit_common vikit_ros image_transport - DEPENDS EIGEN3 PCL OpenCV Sophus -) - # Include directories for dependencies include_directories( - ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} ${PCL_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS} ${Sophus_INCLUDE_DIRS} + ${vikit_common_INCLUDE_DIRS} + ${vikit_ros_INCLUDE_DIRS} include ) +set(dependencies + rclcpp + rclpy + geometry_msgs + nav_msgs + sensor_msgs + visualization_msgs + cv_bridge + vikit_common + vikit_ros + image_transport + pcl_ros + pcl_conversions + tf2_ros + livox_ros_driver2 +) + +set(COMMON_DEPENDENCIES OpenMP::OpenMP_CXX) + +# link_directories(${COMMON_DEPENDENCIES} +# ${vikit_common_LIBRARIES}/libvikit_common.so +# ${vikit_ros_LIBRARIES}/libvikit_ros.so +# ) + # Add libraries add_library(vio src/vio.cpp src/frame.cpp src/visual_point.cpp) add_library(lio src/voxel_map.cpp) add_library(pre src/preprocess.cpp) add_library(imu_proc src/IMU_Processing.cpp) add_library(laser_mapping src/LIVMapper.cpp) +add_library(utils src/utils.cpp) + +ament_target_dependencies(vio ${dependencies} ) +ament_target_dependencies(lio ${dependencies}) +ament_target_dependencies(pre ${dependencies}) +ament_target_dependencies(imu_proc ${dependencies}) +ament_target_dependencies(laser_mapping ${dependencies}) + +# 链接库或可执行文件到公共依赖项 +target_link_libraries(laser_mapping + ${CMAKE_SOURCE_DIR}/../../install/vikit_common/lib/libvikit_common.so + ${CMAKE_SOURCE_DIR}/../../install/vikit_ros/lib/libvikit_ros.so + ${COMMON_DEPENDENCIES} +) +target_link_libraries(vio ${COMMON_DEPENDENCIES}) +target_link_libraries(lio utils ${COMMON_DEPENDENCIES}) +target_link_libraries(pre ${COMMON_DEPENDENCIES}) +target_link_libraries(imu_proc ${COMMON_DEPENDENCIES}) # Add the main executable add_executable(fastlivo_mapping src/main.cpp) +ament_target_dependencies(fastlivo_mapping ${dependencies}) + # Link libraries to the executable target_link_libraries(fastlivo_mapping laser_mapping @@ -133,7 +169,6 @@ target_link_libraries(fastlivo_mapping lio pre imu_proc - ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} ${Sophus_LIBRARIES} @@ -143,4 +178,34 @@ target_link_libraries(fastlivo_mapping # Link mimalloc if found if(mimalloc_FOUND) target_link_libraries(fastlivo_mapping mimalloc) -endif() \ No newline at end of file +endif() + +# Install the executable +install(TARGETS + fastlivo_mapping + DESTINATION lib/${PROJECT_NAME} +) + +install( + DIRECTORY config launch rviz_cfg + DESTINATION share/${PROJECT_NAME} +) + +# Export dependencies +ament_export_dependencies( + rclcpp + rclpy + geometry_msgs + nav_msgs + sensor_msgs + pcl_ros + pcl_conversions + tf2_ros + livox_ros_driver2 + Eigen3 + PCL + OpenCV + Sophus +) + +ament_package() \ No newline at end of file diff --git a/include/IMU_Processing.h b/include/IMU_Processing.h index 6774142a..2a045fa6 100644 --- a/include/IMU_Processing.h +++ b/include/IMU_Processing.h @@ -14,9 +14,10 @@ which is included as part of this source code package. #define IMU_PROCESSING_H #include +#include #include "common_lib.h" #include -#include +#include #include const bool time_list(PointType &x, @@ -32,7 +33,7 @@ class ImuProcess ~ImuProcess(); void Reset(); - void Reset(double start_timestamp, const sensor_msgs::ImuConstPtr &lastimu); + void Reset(double start_timestamp, const sensor_msgs::msg::Imu::ConstSharedPtr &lastimu); void set_extrinsic(const V3D &transl, const M3D &rot); void set_extrinsic(const V3D &transl); void set_extrinsic(const MD(4, 4) & T); @@ -69,7 +70,7 @@ class ImuProcess void IMU_init(const MeasureGroup &meas, StatesGroup &state, int &N); void Forward_without_imu(LidarMeasureGroup &meas, StatesGroup &state_inout, PointCloudXYZI &pcl_out); PointCloudXYZI pcl_wait_proc; - sensor_msgs::ImuConstPtr last_imu; + sensor_msgs::msg::Imu::ConstSharedPtr last_imu; PointCloudXYZI::Ptr cur_pcl_un_; vector IMUpose; M3D Lid_rot_to_IMU; diff --git a/include/LIVMapper.h b/include/LIVMapper.h index 73a562d6..fc127bd4 100644 --- a/include/LIVMapper.h +++ b/include/LIVMapper.h @@ -17,19 +17,21 @@ which is included as part of this source code package. #include "vio.h" #include "preprocess.h" #include -#include -#include +#include +#include +#include +#include #include class LIVMapper { public: - LIVMapper(ros::NodeHandle &nh); + LIVMapper(rclcpp::Node::SharedPtr &node, std::string node_name); ~LIVMapper(); - void initializeSubscribersAndPublishers(ros::NodeHandle &nh, image_transport::ImageTransport &it); - void initializeComponents(); + void initializeSubscribersAndPublishers(rclcpp::Node::SharedPtr &nh, image_transport::ImageTransport &it_); + void initializeComponents(rclcpp::Node::SharedPtr &node); void initializeFiles(); - void run(); + void run(rclcpp::Node::SharedPtr &node); void gravityAlignment(); void handleFirstFrame(); void stateEstimationAndMapping(); @@ -40,27 +42,27 @@ class LIVMapper bool sync_packages(LidarMeasureGroup &meas); void prop_imu_once(StatesGroup &imu_prop_state, const double dt, V3D acc_avr, V3D angvel_avr); - void imu_prop_callback(const ros::TimerEvent &e); + void imu_prop_callback(); void transformLidar(const Eigen::Matrix3d rot, const Eigen::Vector3d t, const PointCloudXYZI::Ptr &input_cloud, PointCloudXYZI::Ptr &trans_cloud); void pointBodyToWorld(const PointType &pi, PointType &po); void RGBpointBodyToWorld(PointType const *const pi, PointType *const po); - void standard_pcl_cbk(const sensor_msgs::PointCloud2::ConstPtr &msg); - void livox_pcl_cbk(const livox_ros_driver::CustomMsg::ConstPtr &msg_in); - void imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in); - void img_cbk(const sensor_msgs::ImageConstPtr &msg_in); + void standard_pcl_cbk(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); + void livox_pcl_cbk(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg_in); + void imu_cbk(const sensor_msgs::msg::Imu::ConstSharedPtr &msg_in); + void img_cbk(const sensor_msgs::msg::Image::ConstSharedPtr &msg_in); void publish_img_rgb(const image_transport::Publisher &pubImage, VIOManagerPtr vio_manager); - void publish_frame_world(const ros::Publisher &pubLaserCloudFullRes, VIOManagerPtr vio_manager); - void publish_visual_sub_map(const ros::Publisher &pubSubVisualMap); - void publish_effect_world(const ros::Publisher &pubLaserCloudEffect, const std::vector &ptpl_list); - void publish_odometry(const ros::Publisher &pubOdomAftMapped); - void publish_mavros(const ros::Publisher &mavros_pose_publisher); - void publish_path(const ros::Publisher pubPath); - void readParameters(ros::NodeHandle &nh); + void publish_frame_world(const rclcpp::Publisher::SharedPtr &pubLaserCloudFullRes, VIOManagerPtr vio_manager); + void publish_visual_sub_map(const rclcpp::Publisher::SharedPtr &pubSubVisualMap); + void publish_effect_world(const rclcpp::Publisher::SharedPtr &pubLaserCloudEffect, const std::vector &ptpl_list); + void publish_odometry(const rclcpp::Publisher::SharedPtr &pmavros_pose_publisherubOdomAftMapped); + void publish_mavros(const rclcpp::Publisher::SharedPtr &mavros_pose_publisher); + void publish_path(const rclcpp::Publisher::SharedPtr &pubPath); + void readParameters(rclcpp::Node::SharedPtr &node); template void set_posestamp(T &out); template void pointBodyToWorld(const Eigen::Matrix &pi, Eigen::Matrix &po); template Eigen::Matrix pointBodyToWorld(const Eigen::Matrix &pi); - cv::Mat getImageFromMsg(const sensor_msgs::ImageConstPtr &img_msg); + cv::Mat getImageFromMsg(const sensor_msgs::msg::Image::ConstSharedPtr &img_msg); std::mutex mtx_buffer, mtx_buffer_imu_prop; std::condition_variable sig_buffer; @@ -91,11 +93,11 @@ class LIVMapper StatesGroup imu_propagate, latest_ekf_state; bool new_imu = false, state_update_flg = false, imu_prop_enable = true, ekf_finish_once = false; - deque prop_imu_buffer; - sensor_msgs::Imu newest_imu; + deque prop_imu_buffer; + sensor_msgs::msg::Imu newest_imu; double latest_ekf_time; - nav_msgs::Odometry imu_prop_odom; - ros::Publisher pubImuPropOdom; + nav_msgs::msg::Odometry imu_prop_odom; + rclcpp::Publisher::SharedPtr pubImuPropOdom; double imu_time_offset = 0.0; bool gravity_align_en = false, gravity_align_finished = false; @@ -119,7 +121,7 @@ class LIVMapper double img_time_offset = 0.0; deque lid_raw_data_buffer; deque lid_header_time_buffer; - deque imu_buffer; + deque imu_buffer; deque img_buffer; deque img_time_buffer; vector _pv_list; @@ -148,34 +150,35 @@ class LIVMapper StatesGroup _state; StatesGroup state_propagat; - nav_msgs::Path path; - nav_msgs::Odometry odomAftMapped; - geometry_msgs::Quaternion geoQuat; - geometry_msgs::PoseStamped msg_body_pose; + nav_msgs::msg::Path path; + nav_msgs::msg::Odometry odomAftMapped; + geometry_msgs::msg::Quaternion geoQuat; + geometry_msgs::msg::PoseStamped msg_body_pose; PreprocessPtr p_pre; ImuProcessPtr p_imu; VoxelMapManagerPtr voxelmap_manager; VIOManagerPtr vio_manager; - ros::Publisher plane_pub; - ros::Publisher voxel_pub; - ros::Subscriber sub_pcl; - ros::Subscriber sub_imu; - ros::Subscriber sub_img; - ros::Publisher pubLaserCloudFullRes; - ros::Publisher pubNormal; - ros::Publisher pubSubVisualMap; - ros::Publisher pubLaserCloudEffect; - ros::Publisher pubLaserCloudMap; - ros::Publisher pubOdomAftMapped; - ros::Publisher pubPath; - ros::Publisher pubLaserCloudDyn; - ros::Publisher pubLaserCloudDynRmed; - ros::Publisher pubLaserCloudDynDbg; + rclcpp::Publisher::SharedPtr plane_pub; + rclcpp::Publisher::SharedPtr voxel_pub; + std::shared_ptr sub_pcl; + rclcpp::Subscription::SharedPtr sub_imu; + rclcpp::Subscription::SharedPtr sub_img; + rclcpp::Publisher::SharedPtr pubLaserCloudFullRes; + rclcpp::Publisher::SharedPtr pubNormal; + rclcpp::Publisher::SharedPtr pubSubVisualMap; + rclcpp::Publisher::SharedPtr pubLaserCloudEffect; + rclcpp::Publisher::SharedPtr pubLaserCloudMap; + rclcpp::Publisher::SharedPtr pubOdomAftMapped; + rclcpp::Publisher::SharedPtr pubPath; + rclcpp::Publisher::SharedPtr pubLaserCloudDyn; + rclcpp::Publisher::SharedPtr pubLaserCloudDynRmed; + rclcpp::Publisher::SharedPtr pubLaserCloudDynDbg; image_transport::Publisher pubImage; - ros::Publisher mavros_pose_publisher; - ros::Timer imu_prop_timer; + rclcpp::Publisher::SharedPtr mavros_pose_publisher; + rclcpp::TimerBase::SharedPtr imu_prop_timer; + rclcpp::Node::SharedPtr node; int frame_num = 0; double aver_time_consu = 0; diff --git a/include/common_lib.h b/include/common_lib.h index 7e72ea73..a3f951d5 100755 --- a/include/common_lib.h +++ b/include/common_lib.h @@ -16,13 +16,16 @@ which is included as part of this source code package. #include #include #include +#include #include -#include -#include -#include +#include +#include +#include +#include +#include using namespace std; -using namespace Eigen; +// using namespace Eigen; // avoid cmake error: reference to ‘Matrix’ is ambiguous using namespace Sophus; #define print_line std::cout << __FILE__ << ", " << __LINE__ << std::endl; @@ -62,7 +65,7 @@ struct MeasureGroup { double vio_time; double lio_time; - deque imu; + deque imu; cv::Mat img; MeasureGroup() { diff --git a/include/feature.h b/include/feature.h index 08a17f87..a94eea74 100644 --- a/include/feature.h +++ b/include/feature.h @@ -33,13 +33,13 @@ struct Feature int level_; //!< Image pyramid level where patch feature was extracted. VisualPoint *point_; //!< Pointer to 3D point which corresponds to the patch feature. Vector2d grad_; //!< Dominant gradient direction for edglets, normalized. - SE3 T_f_w_; //!< Pose of the frame where the patch feature was extracted. + SE3 T_f_w_; //!< Pose of the frame where the patch feature was extracted. float *patch_; //!< Pointer to the image patch data. float score_; //!< Score of the patch feature. float mean_; //!< Mean intensity of the image patch feature, used for normalization. double inv_expo_time_; //!< Inverse exposure time of the image where the patch feature was extracted. - Feature(VisualPoint *_point, float *_patch, const Vector2d &_px, const Vector3d &_f, const SE3 &_T_f_w, int _level) + Feature(VisualPoint *_point, float *_patch, const Vector2d &_px, const Vector3d &_f, const SE3 &_T_f_w, int _level) : type_(CORNER), px_(_px), f_(_f), T_f_w_(_T_f_w), mean_(0), score_(0), level_(_level), patch_(_patch), point_(_point) { } diff --git a/include/frame.h b/include/frame.h index 8172dcdc..ea8a534d 100644 --- a/include/frame.h +++ b/include/frame.h @@ -31,8 +31,8 @@ class Frame : boost::noncopyable static int frame_counter_; //!< Counts the number of created frames. Used to set the unique id. int id_; //!< Unique id of the frame. vk::AbstractCamera *cam_; //!< Camera model. - SE3 T_f_w_; //!< Transform (f)rame from (w)orld. - SE3 T_f_w_prior_; //!< Transform (f)rame from (w)orld provided by the IMU prior. + SE3 T_f_w_; //!< Transform (f)rame from (w)orld. + SE3 T_f_w_prior_; //!< Transform (f)rame from (w)orld provided by the IMU prior. cv::Mat img_; //!< Image of the frame. Features fts_; //!< List of features in the image. diff --git a/include/preprocess.h b/include/preprocess.h index 649ed838..8e99866e 100755 --- a/include/preprocess.h +++ b/include/preprocess.h @@ -14,7 +14,7 @@ which is included as part of this source code package. #define PREPROCESS_H_ #include "common_lib.h" -#include +#include #include using namespace std; @@ -138,11 +138,11 @@ class Preprocess Preprocess(); ~Preprocess(); - void process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); - void process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); + void process(const livox_ros_driver2::msg::CustomMsg::SharedPtr &msg, PointCloudXYZI::Ptr &pcl_out); + void process(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, PointCloudXYZI::Ptr &pcl_out); void set(bool feat_en, int lid_type, double bld, int pfilt_num); - // sensor_msgs::PointCloud2::ConstPtr pointcloud; + // sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud; PointCloudXYZI pl_full, pl_corn, pl_surf; PointCloudXYZI pl_buff[128]; // maximum 128 line lidar vector typess[128]; // maximum 128 line lidar @@ -150,17 +150,19 @@ class Preprocess double blind, blind_sqr; bool feature_enabled, given_offset_time; - ros::Publisher pub_full, pub_surf, pub_corn; + std::shared_ptr> pub_full; + std::shared_ptr> pub_surf; + std::shared_ptr> pub_corn; private: - void avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg); - void oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); - void velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); - void xt32_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); - void Pandar128_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); - void l515_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); + void avia_handler(const livox_ros_driver2::msg::CustomMsg::SharedPtr &msg); + void oust64_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); + void velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); + void xt32_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); + void Pandar128_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); + void l515_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); void give_feature(PointCloudXYZI &pl, vector &types); - void pub_func(PointCloudXYZI &pl, const ros::Time &ct); + void pub_func(PointCloudXYZI &pl, const rclcpp::Time &ct); int plane_judge(const PointCloudXYZI &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); bool small_plane(const PointCloudXYZI &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct); bool edge_jump_judge(const PointCloudXYZI &pl, vector &types, uint i, Surround nor_dir); diff --git a/include/utils/utils.h b/include/utils/utils.h new file mode 100644 index 00000000..9555f705 --- /dev/null +++ b/include/utils/utils.h @@ -0,0 +1,76 @@ +#ifndef UTILS_H +#define UTILS_H + +#include +#include // for int64_t +#include // for std::numeric_limits +#include // for std::out_of_range +#include +#include +#include +#include +#include +#include + +std::vector convertToIntVectorSafe(const std::vector& int64_vector); + +inline double stamp2Sec(const builtin_interfaces::msg::Time& stamp) +{ + return rclcpp::Time(stamp).seconds(); +} + +inline rclcpp::Time sec2Stamp(double timestamp) +{ + int32_t sec = std::floor(timestamp); + auto nanosec_d = (timestamp - std::floor(timestamp)) * 1e9; + uint32_t nanosec = nanosec_d; + return rclcpp::Time(sec, nanosec); +} + +namespace tf +{ + +inline geometry_msgs::msg::Quaternion createQuaternionMsgFromYaw(double yaw) +{ + tf2::Quaternion q; + q.setRPY(0, 0, yaw); + return tf2::toMsg(q); +} + +inline geometry_msgs::msg::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw) +{ + tf2::Quaternion q; + q.setRPY(roll, pitch, yaw); + return tf2::toMsg(q); +} + +inline tf2::Quaternion createQuaternionFromYaw(double yaw) +{ + tf2::Quaternion q; + q.setRPY(0, 0, yaw); + return q; +} + +inline tf2::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw) +{ + tf2::Quaternion q; + q.setRPY(roll, pitch, yaw); + return q; +} +} + +inline geometry_msgs::msg::TransformStamped createTransformStamped( + const tf2::Transform &transform, + const builtin_interfaces::msg::Time &stamp, + const std::string &frame_id, + const std::string &child_frame_id) +{ + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped.header.stamp = stamp; + transform_stamped.header.frame_id = frame_id; + transform_stamped.child_frame_id = child_frame_id; + transform_stamped.transform = tf2::toMsg(transform); + return transform_stamped; +} + +#endif // UTILS_H \ No newline at end of file diff --git a/include/vio.h b/include/vio.h index d5600b1d..21f2d9df 100755 --- a/include/vio.h +++ b/include/vio.h @@ -119,8 +119,8 @@ class VIOManager int frame_count = 0; bool plot_flag; - Matrix G, H_T_H; - MatrixXd K, H_sub_inv; + Eigen::Matrix G, H_T_H; + Eigen::MatrixXd K, H_sub_inv; ofstream fout_camera, fout_colmap; unordered_map feat_map; @@ -153,11 +153,11 @@ class VIOManager void computeJacobianAndUpdateEKF(cv::Mat img); void resetGrid(); void updateVisualMapPoints(cv::Mat img); - void getWarpMatrixAffine(const vk::AbstractCamera &cam, const Vector2d &px_ref, const Vector3d &f_ref, const double depth_ref, const SE3 &T_cur_ref, + void getWarpMatrixAffine(const vk::AbstractCamera &cam, const Vector2d &px_ref, const Vector3d &f_ref, const double depth_ref, const SE3 &T_cur_ref, const int level_ref, const int pyramid_level, const int halfpatch_size, Matrix2d &A_cur_ref); void getWarpMatrixAffineHomography(const vk::AbstractCamera &cam, const V2D &px_ref, - const V3D &xyz_ref, const V3D &normal_ref, const SE3 &T_cur_ref, const int level_ref, Matrix2d &A_cur_ref); + const V3D &xyz_ref, const V3D &normal_ref, const SE3 &T_cur_ref, const int level_ref, Matrix2d &A_cur_ref); void warpAffine(const Matrix2d &A_cur_ref, const cv::Mat &img_ref, const Vector2d &px_ref, const int level_ref, const int search_level, const int pyramid_level, const int halfpatch_size, float *patch); void insertPointIntoVoxelMap(VisualPoint *pt_new); diff --git a/include/voxel_map.h b/include/voxel_map.h index 21afaa34..2f28d80e 100644 --- a/include/voxel_map.h +++ b/include/voxel_map.h @@ -20,12 +20,12 @@ which is included as part of this source code package. #include #include #include -#include +#include #include #include #include -#include -#include +#include +#include #define VOXELMAP_HASH_P 116101 #define VOXELMAP_MAX_N 10000000000 @@ -37,7 +37,7 @@ typedef struct VoxelMapConfig double max_voxel_size_; int max_layer_; int max_iterations_; - std::vector layer_init_num_; + std::vector layer_init_num_; int max_points_num_; double planner_threshold_; double beam_err_; @@ -182,7 +182,7 @@ class VoxelOctoTree VoxelOctoTree *Insert(const pointWithVar &pv); }; -void loadVoxelConfig(ros::NodeHandle &nh, VoxelMapConfig &voxel_config); +void loadVoxelConfig(rclcpp::Node::SharedPtr &node, VoxelMapConfig &voxel_config); class VoxelMapManager { @@ -190,7 +190,7 @@ class VoxelMapManager VoxelMapManager() = default; VoxelMapConfig config_setting_; int current_frame_id_ = 0; - ros::Publisher voxel_map_pub_; + rclcpp::Publisher::SharedPtr voxel_map_pub_; std::unordered_map voxel_map_; PointCloudXYZI::Ptr feats_undistort_; @@ -208,7 +208,7 @@ class VoxelMapManager V3D last_slide_position = {0,0,0}; - geometry_msgs::Quaternion geoQuat_; + geometry_msgs::msg::Quaternion geoQuat_; int feats_down_size_; int effct_feat_num_; @@ -248,9 +248,9 @@ class VoxelMapManager private: void GetUpdatePlane(const VoxelOctoTree *current_octo, const int pub_max_voxel_layer, std::vector &plane_list); - void pubSinglePlane(visualization_msgs::MarkerArray &plane_pub, const std::string plane_ns, const VoxelPlane &single_plane, const float alpha, + void pubSinglePlane(visualization_msgs::msg::MarkerArray &plane_pub, const std::string plane_ns, const VoxelPlane &single_plane, const float alpha, const Eigen::Vector3d rgb); - void CalcVectQuation(const Eigen::Vector3d &x_vec, const Eigen::Vector3d &y_vec, const Eigen::Vector3d &z_vec, geometry_msgs::Quaternion &q); + void CalcVectQuation(const Eigen::Vector3d &x_vec, const Eigen::Vector3d &y_vec, const Eigen::Vector3d &z_vec, geometry_msgs::msg::Quaternion &q); void mapJet(double v, double vmin, double vmax, uint8_t &r, uint8_t &g, uint8_t &b); }; diff --git a/launch/mapping_avia.launch b/launch/mapping_avia.launch deleted file mode 100755 index 1e5c3602..00000000 --- a/launch/mapping_avia.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - -launch-prefix="gdb -ex run --args" -launch-prefix="valgrind --leak-check=full" - diff --git a/package.xml b/package.xml index af3a353c..84a4020e 100755 --- a/package.xml +++ b/package.xml @@ -1,5 +1,5 @@ - + fast_livo 0.0.0 @@ -16,40 +16,39 @@ Ji Zhang - catkin + ament_cmake + + rclcpp + rclpy + sensor_msgs geometry_msgs + visualization_msgs nav_msgs - roscpp - rospy std_msgs - sensor_msgs - tf + tf2_ros pcl_ros - livox_ros_driver - message_generation + pcl_conversions + livox_ros_driver2 vikit_common vikit_ros cv_bridge + image_transport + libopencv-dev + + cv_bridge + image_transport + libopencv-dev + sensor_msgs + std_msgs + + rosidl_interface_packages - geometry_msgs - nav_msgs - sensor_msgs - roscpp - rospy - std_msgs - tf - pcl_ros - livox_ros_driver - message_runtime - vikit_common - vikit_ros - cv_bridge - image_transport - image_transport - - rostest - rosbag + ament_lint_auto + ament_lint_common + ament_cmake + + diff --git a/src/IMU_Processing.cpp b/src/IMU_Processing.cpp index 217511e7..79855525 100755 --- a/src/IMU_Processing.cpp +++ b/src/IMU_Processing.cpp @@ -11,6 +11,7 @@ which is included as part of this source code package. */ #include "IMU_Processing.h" +#include const bool time_list(PointType &x, PointType &y) { return (x.curvature < y.curvature); } @@ -29,7 +30,7 @@ ImuProcess::ImuProcess() : Eye3d(M3D::Identity()), acc_s_last = Zero3d; Lid_offset_to_IMU = Zero3d; Lid_rot_to_IMU = Eye3d; - last_imu.reset(new sensor_msgs::Imu()); + last_imu.reset(new sensor_msgs::msg::Imu()); cur_pcl_un_.reset(new PointCloudXYZI()); } @@ -37,14 +38,14 @@ ImuProcess::~ImuProcess() {} void ImuProcess::Reset() { - ROS_WARN("Reset ImuProcess"); + RCLCPP_WARN(rclcpp::get_logger(""), "Reset ImuProcess"); mean_acc = V3D(0, 0, -1.0); mean_gyr = V3D(0, 0, 0); angvel_last = Zero3d; imu_need_init = true; init_iter_num = 1; IMUpose.clear(); - last_imu.reset(new sensor_msgs::Imu()); + last_imu.reset(new sensor_msgs::msg::Imu()); cur_pcl_un_.reset(new PointCloudXYZI()); } @@ -107,7 +108,7 @@ void ImuProcess::IMU_init(const MeasureGroup &meas, StatesGroup &state_inout, in { /** 1. initializing the gravity, gyro bias, acc and gyro covariance ** 2. normalize the acceleration measurenments to unit gravity **/ - ROS_INFO("IMU Initializing: %.1f %%", double(N) / MAX_INI_COUNT * 100); + RCLCPP_INFO(rclcpp::get_logger(""),"IMU Initializing: %.1f %%", double(N) / MAX_INI_COUNT * 100); V3D cur_acc, cur_gyr; if (b_first_frame) @@ -245,8 +246,8 @@ void ImuProcess::UndistortPcl(LidarMeasureGroup &lidar_meas, StatesGroup &state_ // cout<<"meas.imu.size: "<header.stamp.toSec(); - const double &imu_end_time = v_imu.back()->header.stamp.toSec(); + const double &imu_beg_time = stamp2Sec(v_imu.front()->header.stamp); + const double &imu_end_time = stamp2Sec(v_imu.back()->header.stamp); const double prop_beg_time = last_prop_end_time; // printf("[ IMU ] undistort input size: %zu \n", lidar_meas.pcl_proc_cur->points.size()); // printf("[ IMU ] IMU data sequence size: %zu \n", meas.imu.size()); @@ -307,7 +308,7 @@ void ImuProcess::UndistortPcl(LidarMeasureGroup &lidar_meas, StatesGroup &state_ double tau; if (!imu_time_init) { - // imu_time = v_imu.front()->header.stamp.toSec() - first_lidar_time; + // imu_time = stamp2Sec(v_imu.front()->header.stamp) - first_lidar_time; // tau = 1.0 / (0.25 * sin(2 * CV_PI * 0.5 * imu_time) + 0.75); tau = 1.0; imu_time_init = true; @@ -315,11 +316,10 @@ void ImuProcess::UndistortPcl(LidarMeasureGroup &lidar_meas, StatesGroup &state_ else { tau = state_inout.inv_expo_time; - // ROS_ERROR("tau: %.6f !!!!!!", tau); + // RCLCPP_ERROR_STREAM(rclcpp::get_logger(""),"tau: %.6f !!!!!!", tau); } // state_inout.cov(6, 6) = 0.01; - - // ROS_ERROR("lidar_meas.lio_vio_flg"); + // RCLCPP_ERROR_STREAM(rclcpp::get_logger(""),"lidar_meas.lio_vio_flg"); // cout<<"lidar_meas.lio_vio_flg: "<header.stamp.toSec() < prop_beg_time) continue; + if (stamp2Sec(tail->header.stamp) < prop_beg_time) continue; angvel_avr << 0.5 * (head->angular_velocity.x + tail->angular_velocity.x), 0.5 * (head->angular_velocity.y + tail->angular_velocity.y), 0.5 * (head->angular_velocity.z + tail->angular_velocity.z); @@ -346,30 +346,30 @@ void ImuProcess::UndistortPcl(LidarMeasureGroup &lidar_meas, StatesGroup &state_ // cout<<"acc_avr: "<header.stamp.toSec() - first_lidar_time << " " << angvel_avr.transpose() << " " << acc_avr.transpose() << endl; + fout_imu << setw(10) << stamp2Sec(head->header.stamp) - first_lidar_time << " " << angvel_avr.transpose() << " " << acc_avr.transpose() << endl; // #endif - // imu_time = head->header.stamp.toSec() - first_lidar_time; + // imu_time = stamp2Sec(head->header.stamp) - first_lidar_time; angvel_avr -= state_inout.bias_g; acc_avr = acc_avr * G_m_s2 / mean_acc.norm() - state_inout.bias_a; - if (head->header.stamp.toSec() < prop_beg_time) + if (stamp2Sec(head->header.stamp) < prop_beg_time) { // printf("00 \n"); - dt = tail->header.stamp.toSec() - last_prop_end_time; - offs_t = tail->header.stamp.toSec() - prop_beg_time; + dt = stamp2Sec(tail->header.stamp) - last_prop_end_time; + offs_t = stamp2Sec(tail->header.stamp) - prop_beg_time; } else if (i != v_imu.size() - 2) { // printf("11 \n"); - dt = tail->header.stamp.toSec() - head->header.stamp.toSec(); - offs_t = tail->header.stamp.toSec() - prop_beg_time; + dt = stamp2Sec(tail->header.stamp) - stamp2Sec(head->header.stamp); + offs_t = stamp2Sec(tail->header.stamp) - prop_beg_time; } else { // printf("22 \n"); - dt = prop_end_time - head->header.stamp.toSec(); + dt = prop_end_time - stamp2Sec(head->header.stamp); offs_t = prop_end_time - prop_beg_time; } @@ -426,8 +426,8 @@ void ImuProcess::UndistortPcl(LidarMeasureGroup &lidar_meas, StatesGroup &state_ angvel_last = angvel_avr; acc_s_last = acc_imu; - // cout<header.stamp.toSec(): - // "<header.stamp.toSec()<header.stamp): + // "<header.stamp)< -LIVMapper::LIVMapper(ros::NodeHandle &nh) - : extT(0, 0, 0), +using namespace Sophus; +LIVMapper::LIVMapper(rclcpp::Node::SharedPtr &node, std::string node_name) + : node(std::make_shared(node_name)), + extT(0, 0, 0), extR(M3D::Identity()) { extrinT.assign(3, 0.0); extrinR.assign(9, 0.0); cameraextrinT.assign(3, 0.0); cameraextrinR.assign(9, 0.0); - + p_pre.reset(new Preprocess()); p_imu.reset(new ImuProcess()); - readParameters(nh); + readParameters(this->node); VoxelMapConfig voxel_config; - loadVoxelConfig(nh, voxel_config); + loadVoxelConfig(this->node, voxel_config); visual_sub_map.reset(new PointCloudXYZI()); feats_undistort.reset(new PointCloudXYZI()); @@ -40,86 +43,146 @@ LIVMapper::LIVMapper(ros::NodeHandle &nh) vio_manager.reset(new VIOManager()); root_dir = ROOT_DIR; initializeFiles(); - initializeComponents(); - path.header.stamp = ros::Time::now(); + initializeComponents(this->node); // initialize components errors + path.header.stamp = this->node->now(); path.header.frame_id = "camera_init"; } LIVMapper::~LIVMapper() {} -void LIVMapper::readParameters(ros::NodeHandle &nh) +void LIVMapper::readParameters(rclcpp::Node::SharedPtr &node) { - nh.param("common/lid_topic", lid_topic, "/livox/lidar"); - nh.param("common/imu_topic", imu_topic, "/livox/imu"); - nh.param("common/ros_driver_bug_fix", ros_driver_fix_en, false); - nh.param("common/img_en", img_en, 1); - nh.param("common/lidar_en", lidar_en, 1); - nh.param("common/img_topic", img_topic, "/left_camera/image"); - - nh.param("vio/normal_en", normal_en, true); - nh.param("vio/inverse_composition_en", inverse_composition_en, false); - nh.param("vio/max_iterations", max_iterations, 5); - nh.param("vio/img_point_cov", IMG_POINT_COV, 100); - nh.param("vio/raycast_en", raycast_en, false); - nh.param("vio/exposure_estimate_en", exposure_estimate_en, true); - nh.param("vio/inv_expo_cov", inv_expo_cov, 0.2); - nh.param("vio/grid_size", grid_size, 5); - nh.param("vio/grid_n_height", grid_n_height, 17); - nh.param("vio/patch_pyrimid_level", patch_pyrimid_level, 3); - nh.param("vio/patch_size", patch_size, 8); - nh.param("vio/outlier_threshold", outlier_threshold, 1000); - - nh.param("time_offset/exposure_time_init", exposure_time_init, 0.0); - nh.param("time_offset/img_time_offset", img_time_offset, 0.0); - nh.param("time_offset/imu_time_offset", imu_time_offset, 0.0); - nh.param("uav/imu_rate_odom", imu_prop_enable, false); - nh.param("uav/gravity_align_en", gravity_align_en, false); - - nh.param("evo/seq_name", seq_name, "01"); - nh.param("evo/pose_output_en", pose_output_en, false); - nh.param("imu/gyr_cov", gyr_cov, 1.0); - nh.param("imu/acc_cov", acc_cov, 1.0); - nh.param("imu/imu_int_frame", imu_int_frame, 3); - nh.param("imu/imu_en", imu_en, false); - nh.param("imu/gravity_est_en", gravity_est_en, true); - nh.param("imu/ba_bg_est_en", ba_bg_est_en, true); - - nh.param("preprocess/blind", p_pre->blind, 0.01); - nh.param("preprocess/filter_size_surf", filter_size_surf_min, 0.5); - nh.param("preprocess/lidar_type", p_pre->lidar_type, AVIA); - nh.param("preprocess/scan_line", p_pre->N_SCANS, 6); - nh.param("preprocess/point_filter_num", p_pre->point_filter_num, 3); - nh.param("preprocess/feature_extract_enabled", p_pre->feature_enabled, false); - - nh.param("pcd_save/interval", pcd_save_interval, -1); - nh.param("pcd_save/pcd_save_en", pcd_save_en, false); - nh.param("pcd_save/colmap_output_en", colmap_output_en, false); - nh.param("pcd_save/filter_size_pcd", filter_size_pcd, 0.5); - nh.param>("extrin_calib/extrinsic_T", extrinT, vector()); - nh.param>("extrin_calib/extrinsic_R", extrinR, vector()); - nh.param>("extrin_calib/Pcl", cameraextrinT, vector()); - nh.param>("extrin_calib/Rcl", cameraextrinR, vector()); - nh.param("debug/plot_time", plot_time, -10); - nh.param("debug/frame_cnt", frame_cnt, 6); - - nh.param("publish/blind_rgb_points", blind_rgb_points, 0.01); - nh.param("publish/pub_scan_num", pub_scan_num, 1); - nh.param("publish/pub_effect_point_en", pub_effect_point_en, false); - nh.param("publish/dense_map_en", dense_map_en, false); - - p_pre->blind_sqr = p_pre->blind * p_pre->blind; + // declare parameters + this->node->declare_parameter("common/lid_topic", "/livox/lidar"); + this->node->declare_parameter("common/imu_topic", "/livox/imu"); + this->node->declare_parameter("common/ros_driver_bug_fix", false); + this->node->declare_parameter("common/img_en", 1); + this->node->declare_parameter("common/lidar_en", 1); + this->node->declare_parameter("common/img_topic", "/left_camera/image"); + + this->node->declare_parameter("vio/normal_en", true); + this->node->declare_parameter("vio/inverse_composition_en", false); + this->node->declare_parameter("vio/max_iterations", 5); + this->node->declare_parameter("vio/img_point_cov", 100); + this->node->declare_parameter("vio/raycast_en", false); + this->node->declare_parameter("vio/exposure_estimate_en", true); + this->node->declare_parameter("vio/inv_expo_cov", 0.1); + this->node->declare_parameter("vio/grid_size", 5); + this->node->declare_parameter("vio/grid_n_height", 17); + this->node->declare_parameter("vio/patch_pyrimid_level", 4); + this->node->declare_parameter("vio/patch_size", 8); + this->node->declare_parameter("vio/outlier_threshold", 100); + this->node->declare_parameter("time_offset/exposure_time_init", 0.0); + this->node->declare_parameter("time_offset/img_time_offset", 0.0); + this->node->declare_parameter("uav/imu_rate_odom", false); + this->node->declare_parameter("uav/gravity_align_en", false); + + this->node->declare_parameter("evo/seq_name", "01"); + this->node->declare_parameter("evo/pose_output_en", false); + this->node->declare_parameter("imu/gyr_cov", 1.0); + this->node->declare_parameter("imu/acc_cov", 1.0); + this->node->declare_parameter("imu/imu_int_frame", 30); + this->node->declare_parameter("imu/imu_en", true); + this->node->declare_parameter("imu/gravity_est_en", true); + this->node->declare_parameter("imu/ba_bg_est_en", true); + + this->node->declare_parameter("preprocess/blind", 0.01); + this->node->declare_parameter("preprocess/filter_size_surf", 0.5); + this->node->declare_parameter("preprocess/lidar_type", AVIA); + this->node->declare_parameter("preprocess/scan_line",6); + this->node->declare_parameter("preprocess/point_filter_num", 3); + this->node->declare_parameter("preprocess/feature_extract_enabled", false); + + this->node->declare_parameter("pcd_save/interval", -1); + this->node->declare_parameter("pcd_save/pcd_save_en", false); + this->node->declare_parameter("pcd_save/colmap_output_en", false); + this->node->declare_parameter("pcd_save/filter_size_pcd", 0.5); + this->node->declare_parameter>("extrin_calib/extrinsic_T", vector()); + this->node->declare_parameter>("extrin_calib/extrinsic_R", vector()); + this->node->declare_parameter>("extrin_calib/Pcl", vector()); + this->node->declare_parameter>("extrin_calib/Rcl", vector()); + this->node->declare_parameter("debug/plot_time", -10); + this->node->declare_parameter("debug/frame_cnt", 6); + + this->node->declare_parameter("publish/blind_rgb_points", 0.01); + this->node->declare_parameter("publish/pub_scan_num", 1); + this->node->declare_parameter("publish/pub_effect_point_en", false); + this->node->declare_parameter("publish/dense_map_en", false); + + // get parameter + this->node->get_parameter("common/lid_topic", lid_topic); + this->node->get_parameter("common/imu_topic", imu_topic); + this->node->get_parameter("common/ros_driver_bug_fix", ros_driver_fix_en); + this->node->get_parameter("common/img_en", img_en); + this->node->get_parameter("common/lidar_en", lidar_en); + this->node->get_parameter("common/img_topic", img_topic); + + this->node->get_parameter("vio/normal_en", normal_en); + this->node->get_parameter("vio/inverse_composition_en", inverse_composition_en); + this->node->get_parameter("vio/max_iterations", max_iterations); + this->node->get_parameter("vio/img_point_cov", IMG_POINT_COV); + this->node->get_parameter("vio/raycast_en", raycast_en); + this->node->get_parameter("vio/exposure_estimate_en", exposure_estimate_en); + this->node->get_parameter("vio/inv_expo_cov", inv_expo_cov); + this->node->get_parameter("vio/grid_size", grid_size); + this->node->get_parameter("vio/grid_n_height", grid_n_height); + this->node->get_parameter("vio/patch_pyrimid_level", patch_pyrimid_level); + this->node->get_parameter("vio/patch_size", patch_size); + this->node->get_parameter("vio/outlier_threshold", outlier_threshold); + this->node->get_parameter("time_offset/exposure_time_init", exposure_time_init); + this->node->get_parameter("time_offset/img_time_offset", img_time_offset); + this->node->get_parameter("uav/imu_rate_odom", imu_prop_enable); + this->node->get_parameter("uav/gravity_align_en", gravity_align_en); + + this->node->get_parameter("evo/seq_name", seq_name); + this->node->get_parameter("evo/pose_output_en", pose_output_en); + this->node->get_parameter("imu/gyr_cov", gyr_cov); + this->node->get_parameter("imu/acc_cov", acc_cov); + this->node->get_parameter("imu/imu_int_frame", imu_int_frame); + this->node->get_parameter("imu/imu_en", imu_en); + this->node->get_parameter("imu/gravity_est_en", gravity_est_en); + this->node->get_parameter("imu/ba_bg_est_en", ba_bg_est_en); + + this->node->get_parameter("preprocess/blind", p_pre->blind); + this->node->get_parameter("preprocess/filter_size_surf", filter_size_surf_min); + this->node->get_parameter("preprocess/lidar_type", p_pre->lidar_type); + this->node->get_parameter("preprocess/scan_line", p_pre->N_SCANS); + this->node->get_parameter("preprocess/point_filter_num", p_pre->point_filter_num); + this->node->get_parameter("preprocess/feature_extract_enabled", p_pre->feature_enabled); + + this->node->get_parameter("pcd_save/interval", pcd_save_interval); + this->node->get_parameter("pcd_save/pcd_save_en", pcd_save_en); + this->node->get_parameter("pcd_save/colmap_output_en", colmap_output_en); + this->node->get_parameter("pcd_save/filter_size_pcd", filter_size_pcd); + this->node->get_parameter("extrin_calib/extrinsic_T", extrinT); + this->node->get_parameter("extrin_calib/extrinsic_R", extrinR); + this->node->get_parameter("extrin_calib/Pcl", cameraextrinT); + this->node->get_parameter("extrin_calib/Rcl", cameraextrinR); + this->node->get_parameter("debug/plot_time", plot_time); + this->node->get_parameter("debug/frame_cnt", frame_cnt); + + this->node->get_parameter("publish/blind_rgb_points", blind_rgb_points); + this->node->get_parameter("publish/pub_scan_num", pub_scan_num); + this->node->get_parameter("publish/pub_effect_point_en", pub_effect_point_en); + this->node->get_parameter("publish/dense_map_en", dense_map_en); } -void LIVMapper::initializeComponents() +void LIVMapper::initializeComponents(rclcpp::Node::SharedPtr &node) { downSizeFilterSurf.setLeafSize(filter_size_surf_min, filter_size_surf_min, filter_size_surf_min); + + extrinT.assign({0.04165, 0.02326, -0.0284}); + extrinR.assign({1, 0, 0, 0, 1, 0, 0, 0, 1}); + cameraextrinT.assign({0.0194384, 0.104689,-0.0251952}); + cameraextrinR.assign({0.00610193,-0.999863,-0.0154172,-0.00615449,0.0153796,-0.999863,0.999962,0.00619598,-0.0060598}); + extT << VEC_FROM_ARRAY(extrinT); extR << MAT_FROM_ARRAY(extrinR); voxelmap_manager->extT_ << VEC_FROM_ARRAY(extrinT); voxelmap_manager->extR_ << MAT_FROM_ARRAY(extrinR); - if (!vk::camera_loader::loadFromRosNs("laserMapping", vio_manager->cam)) throw std::runtime_error("Camera model not correctly specified."); + if (!vk::camera_loader::loadFromRosNs(this->node, "laserMapping", vio_manager->cam)) throw std::runtime_error("Camera model not correctly specified."); vio_manager->grid_size = grid_size; vio_manager->patch_size = patch_size; @@ -182,31 +245,34 @@ void LIVMapper::initializeFiles() fout_out.open(DEBUG_FILE_DIR("mat_out.txt"), std::ios::out); } -void LIVMapper::initializeSubscribersAndPublishers(ros::NodeHandle &nh, image_transport::ImageTransport &it) +void LIVMapper::initializeSubscribersAndPublishers(rclcpp::Node::SharedPtr &node, image_transport::ImageTransport &it_) { - sub_pcl = p_pre->lidar_type == AVIA ? - nh.subscribe(lid_topic, 200000, &LIVMapper::livox_pcl_cbk, this): - nh.subscribe(lid_topic, 200000, &LIVMapper::standard_pcl_cbk, this); - sub_imu = nh.subscribe(imu_topic, 200000, &LIVMapper::imu_cbk, this); - sub_img = nh.subscribe(img_topic, 200000, &LIVMapper::img_cbk, this); + image_transport::ImageTransport it(this->node); + if (p_pre->lidar_type == AVIA) { + sub_pcl = this->node->create_subscription(lid_topic, 200000, std::bind(&LIVMapper::livox_pcl_cbk, this, std::placeholders::_1)); + } else { + sub_pcl = this->node->create_subscription(lid_topic, 200000, std::bind(&LIVMapper::standard_pcl_cbk, this, std::placeholders::_1)); + } + sub_imu = this->node->create_subscription(imu_topic, 200000, std::bind(&LIVMapper::imu_cbk, this, std::placeholders::_1)); + sub_img = this->node->create_subscription(img_topic, 200000, std::bind(&LIVMapper::img_cbk, this, std::placeholders::_1)); - pubLaserCloudFullRes = nh.advertise("/cloud_registered", 100); - pubNormal = nh.advertise("visualization_marker", 100); - pubSubVisualMap = nh.advertise("/cloud_visual_sub_map_before", 100); - pubLaserCloudEffect = nh.advertise("/cloud_effected", 100); - pubLaserCloudMap = nh.advertise("/Laser_map", 100); - pubOdomAftMapped = nh.advertise("/aft_mapped_to_init", 10); - pubPath = nh.advertise("/path", 10); - plane_pub = nh.advertise("/planner_normal", 1); - voxel_pub = nh.advertise("/voxels", 1); - pubLaserCloudDyn = nh.advertise("/dyn_obj", 100); - pubLaserCloudDynRmed = nh.advertise("/dyn_obj_removed", 100); - pubLaserCloudDynDbg = nh.advertise("/dyn_obj_dbg_hist", 100); - mavros_pose_publisher = nh.advertise("/mavros/vision_pose/pose", 10); + pubLaserCloudFullRes = this->node->create_publisher("/cloud_registered", 100); + pubNormal = this->node->create_publisher("/visualization_marker", 100); + pubSubVisualMap = this->node->create_publisher("/cloud_visual_sub_map_before", 100); + pubLaserCloudEffect = this->node->create_publisher("/cloud_effected", 100); + pubLaserCloudMap = this->node->create_publisher("/Laser_map", 100); + pubOdomAftMapped = this->node->create_publisher("/aft_mapped_to_init", 10); + pubPath = this->node->create_publisher("/path", 10); + plane_pub = this->node->create_publisher("/planner_normal", 1); + voxel_pub = this->node->create_publisher("/voxels", 1); + pubLaserCloudDyn = this->node->create_publisher("/dyn_obj", 100); + pubLaserCloudDynRmed = this->node->create_publisher("/dyn_obj_removed", 100); + pubLaserCloudDynDbg = this->node->create_publisher("/dyn_obj_dbg_hist", 100); + mavros_pose_publisher = this->node->create_publisher("/mavros/vision_pose/pose", 10); pubImage = it.advertise("/rgb_img", 1); - pubImuPropOdom = nh.advertise("/LIVO2/imu_propagate", 10000); - imu_prop_timer = nh.createTimer(ros::Duration(0.004), &LIVMapper::imu_prop_callback, this); - voxelmap_manager->voxel_map_pub_= nh.advertise("/planes", 10000); + pubImuPropOdom = this->node->create_publisher("/LIVO2/imu_propagate", 10000); + imu_prop_timer = this->node->create_wall_timer(0.004s, std::bind(&LIVMapper::imu_prop_callback, this)); + voxelmap_manager->voxel_map_pub_= this->node->create_publisher("/planes", 10000); } void LIVMapper::handleFirstFrame() @@ -226,7 +292,7 @@ void LIVMapper::gravityAlignment() { std::cout << "Gravity Alignment Starts" << std::endl; V3D ez(0, 0, -1), gz(_state.gravity); - Quaterniond G_q_I0 = Quaterniond::FromTwoVectors(gz, ez); + Eigen::Quaterniond G_q_I0 = Eigen::Quaterniond::FromTwoVectors(gz, ez); M3D G_R_I0 = G_q_I0.toRotationMatrix(); _state.pos_end = G_R_I0 * _state.pos_end; @@ -383,12 +449,12 @@ void LIVMapper::handleLIO() { evoFile.open(std::string(ROOT_DIR) + "Log/result/" + seq_name + ".txt", std::ios::out); pos_opend = true; - if (!evoFile.is_open()) ROS_ERROR("open fail\n"); + if (!evoFile.is_open()) RCLCPP_ERROR(this->node->get_logger(), "open fail\n"); } else { evoFile.open(std::string(ROOT_DIR) + "Log/result/" + seq_name + ".txt", std::ios::app); - if (!evoFile.is_open()) ROS_ERROR("open fail\n"); + if (!evoFile.is_open()) RCLCPP_ERROR(this->node->get_logger(), "open fail\n"); } Eigen::Matrix4d outT; Eigen::Quaterniond q(_state.rot_end); @@ -524,12 +590,12 @@ void LIVMapper::savePCD() } } -void LIVMapper::run() +void LIVMapper::run(rclcpp::Node::SharedPtr &node) { - ros::Rate rate(5000); - while (ros::ok()) + rclcpp::Rate rate(5000); + while (rclcpp::ok()) { - ros::spinOnce(); + rclcpp::spin_some(this->node); if (!sync_packages(LidarMeasures)) { rate.sleep(); @@ -566,11 +632,11 @@ void LIVMapper::prop_imu_once(StatesGroup &imu_prop_state, const double dt, V3D imu_prop_state.vel_end = imu_prop_state.vel_end + acc_imu * dt; } -void LIVMapper::imu_prop_callback(const ros::TimerEvent &e) +void LIVMapper::imu_prop_callback() { if (p_imu->imu_need_init || !new_imu || !ekf_finish_once) { return; } mtx_buffer_imu_prop.lock(); - new_imu = false; // 控制propagate频率和IMU频率一致 + new_imu = false; // 控制 propagate 频率和 IMU 频率一致 if (imu_prop_enable && !prop_imu_buffer.empty()) { static double last_t_from_lidar_end_time = 0; @@ -578,14 +644,14 @@ void LIVMapper::imu_prop_callback(const ros::TimerEvent &e) { imu_propagate = latest_ekf_state; // drop all useless imu pkg - while ((!prop_imu_buffer.empty() && prop_imu_buffer.front().header.stamp.toSec() < latest_ekf_time)) + while ((!prop_imu_buffer.empty() && stamp2Sec(prop_imu_buffer.front().header.stamp) < latest_ekf_time)) { prop_imu_buffer.pop_front(); } last_t_from_lidar_end_time = 0; for (int i = 0; i < prop_imu_buffer.size(); i++) { - double t_from_lidar_end_time = prop_imu_buffer[i].header.stamp.toSec() - latest_ekf_time; + double t_from_lidar_end_time = stamp2Sec(prop_imu_buffer[i].header.stamp) - latest_ekf_time; double dt = t_from_lidar_end_time - last_t_from_lidar_end_time; // cout << "prop dt" << dt << ", " << t_from_lidar_end_time << ", " << last_t_from_lidar_end_time << endl; V3D acc_imu(prop_imu_buffer[i].linear_acceleration.x, prop_imu_buffer[i].linear_acceleration.y, prop_imu_buffer[i].linear_acceleration.z); @@ -599,7 +665,7 @@ void LIVMapper::imu_prop_callback(const ros::TimerEvent &e) { V3D acc_imu(newest_imu.linear_acceleration.x, newest_imu.linear_acceleration.y, newest_imu.linear_acceleration.z); V3D omg_imu(newest_imu.angular_velocity.x, newest_imu.angular_velocity.y, newest_imu.angular_velocity.z); - double t_from_lidar_end_time = newest_imu.header.stamp.toSec() - latest_ekf_time; + double t_from_lidar_end_time = stamp2Sec(newest_imu.header.stamp) - latest_ekf_time; double dt = t_from_lidar_end_time - last_t_from_lidar_end_time; prop_imu_once(imu_propagate, dt, acc_imu, omg_imu); last_t_from_lidar_end_time = t_from_lidar_end_time; @@ -622,7 +688,7 @@ void LIVMapper::imu_prop_callback(const ros::TimerEvent &e) imu_prop_odom.twist.twist.linear.x = vel_i.x(); imu_prop_odom.twist.twist.linear.y = vel_i.y(); imu_prop_odom.twist.twist.linear.z = vel_i.z(); - pubImuPropOdom.publish(imu_prop_odom); + pubImuPropOdom->publish(imu_prop_odom); } mtx_buffer_imu_prop.unlock(); } @@ -668,7 +734,7 @@ template Matrix LIVMapper::pointBodyToWorld(const Matrix po(p[0], p[1], p[2]); + Eigen::Matrix po(p[0], p[1], p[2]); return po; } @@ -682,53 +748,53 @@ void LIVMapper::RGBpointBodyToWorld(PointType const *const pi, PointType *const po->intensity = pi->intensity; } -void LIVMapper::standard_pcl_cbk(const sensor_msgs::PointCloud2::ConstPtr &msg) +void LIVMapper::standard_pcl_cbk(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { if (!lidar_en) return; mtx_buffer.lock(); // cout<<"got feature"<header.stamp.toSec() < last_timestamp_lidar) + if (stamp2Sec(msg->header.stamp) < last_timestamp_lidar) { - ROS_ERROR("lidar loop back, clear buffer"); + RCLCPP_ERROR(this->node->get_logger(),"lidar loop back, clear buffer"); lid_raw_data_buffer.clear(); } - // ROS_INFO("get point cloud at time: %.6f", msg->header.stamp.toSec()); + // ROS_INFO("get point cloud at time: %.6f", stamp2Sec(msg->header.stamp)); PointCloudXYZI::Ptr ptr(new PointCloudXYZI()); p_pre->process(msg, ptr); lid_raw_data_buffer.push_back(ptr); - lid_header_time_buffer.push_back(msg->header.stamp.toSec()); - last_timestamp_lidar = msg->header.stamp.toSec(); + lid_header_time_buffer.push_back(stamp2Sec(msg->header.stamp)); + last_timestamp_lidar = stamp2Sec(msg->header.stamp); mtx_buffer.unlock(); sig_buffer.notify_all(); } -void LIVMapper::livox_pcl_cbk(const livox_ros_driver::CustomMsg::ConstPtr &msg_in) +void LIVMapper::livox_pcl_cbk(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg_in) { if (!lidar_en) return; mtx_buffer.lock(); - livox_ros_driver::CustomMsg::Ptr msg(new livox_ros_driver::CustomMsg(*msg_in)); - // if ((abs(msg->header.stamp.toSec() - last_timestamp_lidar) > 0.2 && last_timestamp_lidar > 0) || sync_jump_flag) + livox_ros_driver2::msg::CustomMsg::SharedPtr msg(new livox_ros_driver2::msg::CustomMsg(*msg_in)); + // if ((abs(stamp2Sec(msg->header.stamp) - last_timestamp_lidar) > 0.2 && last_timestamp_lidar > 0) || sync_jump_flag) // { - // ROS_WARN("lidar jumps %.3f\n", msg->header.stamp.toSec() - last_timestamp_lidar); + // ROS_WARN("lidar jumps %.3f\n", stamp2Sec(msg->header.stamp) - last_timestamp_lidar); // sync_jump_flag = true; - // msg->header.stamp = ros::Time().fromSec(last_timestamp_lidar + 0.1); + // msg->header.stamp = rclcpp::Time().fromSec(last_timestamp_lidar + 0.1); // } - if (abs(last_timestamp_imu - msg->header.stamp.toSec()) > 1.0 && !imu_buffer.empty()) + if (abs(last_timestamp_imu - stamp2Sec(msg->header.stamp)) > 1.0 && !imu_buffer.empty()) { - double timediff_imu_wrt_lidar = last_timestamp_imu - msg->header.stamp.toSec(); - printf("\033[95mSelf sync IMU and LiDAR, HARD time lag is %.10lf \n\033[0m", timediff_imu_wrt_lidar - 0.100); + double timediff_imu_wrt_lidar = last_timestamp_imu - stamp2Sec(msg->header.stamp); + RCLCPP_INFO(this->node->get_logger(), "\033[95mSelf sync IMU and LiDAR, HARD time lag is %.10lf \n\033[0m", timediff_imu_wrt_lidar - 0.100); // imu_time_offset = timediff_imu_wrt_lidar; } - double cur_head_time = msg->header.stamp.toSec(); - ROS_INFO("Get LiDAR, its header time: %.6f", cur_head_time); + double cur_head_time = stamp2Sec(msg->header.stamp); + RCLCPP_INFO(this->node->get_logger(), "Get LiDAR, its header time: %.6f", cur_head_time); if (cur_head_time < last_timestamp_lidar) { - ROS_ERROR("lidar loop back, clear buffer"); + RCLCPP_ERROR(this->node->get_logger(), "lidar loop back, clear buffer"); lid_raw_data_buffer.clear(); } - // ROS_INFO("get point cloud at time: %.6f", msg->header.stamp.toSec()); + RCLCPP_INFO(this->node->get_logger(), "get point cloud at time: %.6f", stamp2Sec(msg->header.stamp)); PointCloudXYZI::Ptr ptr(new PointCloudXYZI()); p_pre->process(msg, ptr); @@ -746,23 +812,23 @@ void LIVMapper::livox_pcl_cbk(const livox_ros_driver::CustomMsg::ConstPtr &msg_i sig_buffer.notify_all(); } -void LIVMapper::imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in) +void LIVMapper::imu_cbk(const sensor_msgs::msg::Imu::ConstSharedPtr &msg_in) { if (!imu_en) return; if (last_timestamp_lidar < 0.0) return; - // ROS_INFO("get imu at time: %.6f", msg_in->header.stamp.toSec()); - sensor_msgs::Imu::Ptr msg(new sensor_msgs::Imu(*msg_in)); - msg->header.stamp = ros::Time().fromSec(msg->header.stamp.toSec() - imu_time_offset); - double timestamp = msg->header.stamp.toSec(); + RCLCPP_INFO(this->node->get_logger(), "get imu at time: %.6f", stamp2Sec(msg_in->header.stamp)); + sensor_msgs::msg::Imu::SharedPtr msg(new sensor_msgs::msg::Imu(*msg_in)); + msg->header.stamp = sec2Stamp(stamp2Sec(msg->header.stamp) - imu_time_offset); + double timestamp = stamp2Sec(msg->header.stamp); if (fabs(last_timestamp_lidar - timestamp) > 0.5 && (!ros_driver_fix_en)) { - ROS_WARN("IMU and LiDAR not synced! delta time: %lf .\n", last_timestamp_lidar - timestamp); + RCLCPP_WARN(this->node->get_logger(), "IMU and LiDAR not synced! delta time: %lf .\n", last_timestamp_lidar - timestamp); } if (ros_driver_fix_en) timestamp += std::round(last_timestamp_lidar - timestamp); - msg->header.stamp = ros::Time().fromSec(timestamp); + msg->header.stamp = sec2Stamp(timestamp); mtx_buffer.lock(); @@ -770,23 +836,22 @@ void LIVMapper::imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in) { mtx_buffer.unlock(); sig_buffer.notify_all(); - ROS_ERROR("imu loop back, offset: %lf \n", last_timestamp_imu - timestamp); + RCLCPP_ERROR(this->node->get_logger(), "imu loop back, offset: %lf \n", last_timestamp_imu - timestamp); return; } - // if (last_timestamp_imu > 0.0 && timestamp > last_timestamp_imu + 0.2) - // { - - // ROS_WARN("imu time stamp Jumps %0.4lf seconds \n", timestamp - last_timestamp_imu); - // mtx_buffer.unlock(); - // sig_buffer.notify_all(); - // return; - // } + if (last_timestamp_imu > 0.0 && timestamp > last_timestamp_imu + 0.2) + { + RCLCPP_WARN(this->node->get_logger(), "imu time stamp Jumps %0.4lf seconds \n", timestamp - last_timestamp_imu); + mtx_buffer.unlock(); + sig_buffer.notify_all(); + return; + } last_timestamp_imu = timestamp; imu_buffer.push_back(msg); - // cout<<"got imu: "<image; + img = cv_bridge::toCvShare(img_msg, "bgr8")->image; return img; } // static int i = 0; -void LIVMapper::img_cbk(const sensor_msgs::ImageConstPtr &msg_in) +void LIVMapper::img_cbk(const sensor_msgs::msg::Image::ConstSharedPtr &msg_in) { if (!img_en) return; - sensor_msgs::Image::Ptr msg(new sensor_msgs::Image(*msg_in)); - // if ((abs(msg->header.stamp.toSec() - last_timestamp_img) > 0.2 && last_timestamp_img > 0) || sync_jump_flag) + sensor_msgs::msg::Image::SharedPtr msg(new sensor_msgs::msg::Image(*msg_in)); + // if ((abs(stamp2Sec(msg->header.stamp) - last_timestamp_img) > 0.2 && last_timestamp_img > 0) || sync_jump_flag) // { - // ROS_WARN("img jumps %.3f\n", msg->header.stamp.toSec() - last_timestamp_img); + // RCLCPP_WARN(this->node->get_logger(), "img jumps %.3f\n", stamp2Sec(msg->header.stamp) - last_timestamp_img); // sync_jump_flag = true; - // msg->header.stamp = ros::Time().fromSec(last_timestamp_img + 0.1); + // msg->header.stamp = rclcpp::Time().fromSec(last_timestamp_img + 0.1); // } // Hiliti2022 40Hz @@ -824,15 +889,15 @@ void LIVMapper::img_cbk(const sensor_msgs::ImageConstPtr &msg_in) // i++; // if (i % 4 != 0) return; // } - // double msg_header_time = msg->header.stamp.toSec(); - double msg_header_time = msg->header.stamp.toSec() + img_time_offset; + // double msg_header_time = stamp2Sec(msg->header.stamp); + double msg_header_time = stamp2Sec(msg->header.stamp) + img_time_offset; if (abs(msg_header_time - last_timestamp_img) < 0.001) return; - ROS_INFO("Get image, its header time: %.6f", msg_header_time); + RCLCPP_INFO(this->node->get_logger(), "Get image, its header time: %.6f", msg_header_time); if (last_timestamp_lidar < 0) return; if (msg_header_time < last_timestamp_img) { - ROS_ERROR("image loop back. \n"); + RCLCPP_ERROR(this->node->get_logger(), "image loop back. \n"); return; } @@ -842,7 +907,7 @@ void LIVMapper::img_cbk(const sensor_msgs::ImageConstPtr &msg_in) if (img_time_correct - last_timestamp_img < 0.02) { - ROS_WARN("Image need Jumps: %.6f", img_time_correct); + RCLCPP_WARN(this->node->get_logger(), "Image need Jumps: %.6f", img_time_correct); mtx_buffer.unlock(); sig_buffer.notify_all(); return; @@ -900,7 +965,7 @@ bool LIVMapper::sync_packages(LidarMeasureGroup &meas) mtx_buffer.lock(); while (!imu_buffer.empty()) { - if (imu_buffer.front()->header.stamp.toSec() > meas.lidar_frame_end_time) break; + if (stamp2Sec(imu_buffer.front()->header.stamp) > meas.lidar_frame_end_time) break; m.imu.push_back(imu_buffer.front()); imu_buffer.pop_front(); } @@ -941,19 +1006,19 @@ bool LIVMapper::sync_packages(LidarMeasureGroup &meas) // meas.last_lio_update_time); double lid_newest_time = lid_header_time_buffer.back() + lid_raw_data_buffer.back()->points.back().curvature / double(1000); - double imu_newest_time = imu_buffer.back()->header.stamp.toSec(); + double imu_newest_time = stamp2Sec(imu_buffer.back()->header.stamp); if (img_capture_time < meas.last_lio_update_time + 0.00001) { img_buffer.pop_front(); img_time_buffer.pop_front(); - ROS_ERROR("[ Data Cut ] Throw one image frame! \n"); + RCLCPP_ERROR(this->node->get_logger(), "[ Data Cut ] Throw one image frame! \n"); return false; } if (img_capture_time > lid_newest_time || img_capture_time > imu_newest_time) { - // ROS_ERROR("lost first camera frame"); + // RCLCPP_ERROR(this->node->get_logger(), "lost first camera frame"); // printf("img_capture_time, lid_newest_time, imu_newest_time: %lf , %lf // , %lf \n", img_capture_time, lid_newest_time, imu_newest_time); return false; @@ -968,13 +1033,13 @@ bool LIVMapper::sync_packages(LidarMeasureGroup &meas) mtx_buffer.lock(); while (!imu_buffer.empty()) { - if (imu_buffer.front()->header.stamp.toSec() > m.lio_time) break; + if (stamp2Sec(imu_buffer.front()->header.stamp) > m.lio_time) break; - if (imu_buffer.front()->header.stamp.toSec() > meas.last_lio_update_time) m.imu.push_back(imu_buffer.front()); + if (stamp2Sec(imu_buffer.front()->header.stamp) > meas.last_lio_update_time) m.imu.push_back(imu_buffer.front()); imu_buffer.pop_front(); // printf("[ Data Cut ] imu time: %lf \n", - // imu_buffer.front()->header.stamp.toSec()); + // stamp2Sec(imu_buffer.front()->header.stamp)); } mtx_buffer.unlock(); sig_buffer.notify_all(); @@ -1029,7 +1094,7 @@ bool LIVMapper::sync_packages(LidarMeasureGroup &meas) meas.lio_vio_flg = VIO; // printf("[ Data Cut ] VIO \n"); meas.measures.clear(); - double imu_time = imu_buffer.front()->header.stamp.toSec(); + double imu_time = stamp2Sec(imu_buffer.front()->header.stamp); struct MeasureGroup m; m.vio_time = img_capture_time; @@ -1038,12 +1103,12 @@ bool LIVMapper::sync_packages(LidarMeasureGroup &meas) mtx_buffer.lock(); // while ((!imu_buffer.empty() && (imu_time < img_capture_time))) // { - // imu_time = imu_buffer.front()->header.stamp.toSec(); + // imu_time = stamp2Sec(imu_buffer.front()->header.stamp); // if (imu_time > img_capture_time) break; // m.imu.push_back(imu_buffer.front()); // imu_buffer.pop_front(); // printf("[ Data Cut ] imu time: %lf \n", - // imu_buffer.front()->header.stamp.toSec()); + // stamp2Sec(imu_buffer.front()->header.stamp)); // } img_buffer.pop_front(); img_time_buffer.pop_front(); @@ -1096,21 +1161,21 @@ bool LIVMapper::sync_packages(LidarMeasureGroup &meas) return false; } } - ROS_ERROR("out sync"); + RCLCPP_ERROR(this->node->get_logger(), "out sync"); } void LIVMapper::publish_img_rgb(const image_transport::Publisher &pubImage, VIOManagerPtr vio_manager) { cv::Mat img_rgb = vio_manager->img_cp; cv_bridge::CvImage out_msg; - out_msg.header.stamp = ros::Time::now(); + out_msg.header.stamp = this->node->get_clock()->now(); // out_msg.header.frame_id = "camera_init"; out_msg.encoding = sensor_msgs::image_encodings::BGR8; out_msg.image = img_rgb; pubImage.publish(out_msg.toImageMsg()); } -void LIVMapper::publish_frame_world(const ros::Publisher &pubLaserCloudFullRes, VIOManagerPtr vio_manager) +void LIVMapper::publish_frame_world(const rclcpp::Publisher::SharedPtr &pubLaserCloudFullRes, VIOManagerPtr vio_manager) { if (pcl_w_wait_pub->empty()) return; PointCloudXYZRGB::Ptr laserCloudWorldRGB(new PointCloudXYZRGB()); @@ -1160,7 +1225,7 @@ void LIVMapper::publish_frame_world(const ros::Publisher &pubLaserCloudFullRes, } /*** Publish Frame ***/ - sensor_msgs::PointCloud2 laserCloudmsg; + sensor_msgs::msg::PointCloud2 laserCloudmsg; if (img_en) { // cout << "RGB pointcloud size: " << laserCloudWorldRGB->size() << endl; @@ -1170,9 +1235,9 @@ void LIVMapper::publish_frame_world(const ros::Publisher &pubLaserCloudFullRes, { pcl::toROSMsg(*pcl_w_wait_pub, laserCloudmsg); } - laserCloudmsg.header.stamp = ros::Time::now(); //.fromSec(last_timestamp_lidar); + laserCloudmsg.header.stamp = this->node->get_clock()->now(); //.fromSec(last_timestamp_lidar); laserCloudmsg.header.frame_id = "camera_init"; - pubLaserCloudFullRes.publish(laserCloudmsg); + pubLaserCloudFullRes->publish(laserCloudmsg); /**************** save map ****************/ /* 1. make sure you have enough memories @@ -1222,7 +1287,7 @@ void LIVMapper::publish_frame_world(const ros::Publisher &pubLaserCloudFullRes, PointCloudXYZI().swap(*pcl_w_wait_pub); } -void LIVMapper::publish_visual_sub_map(const ros::Publisher &pubSubVisualMap) +void LIVMapper::publish_visual_sub_map(const rclcpp::Publisher::SharedPtr &pubSubVisualMap) { PointCloudXYZI::Ptr laserCloudFullRes(visual_sub_map); int size = laserCloudFullRes->points.size(); if (size == 0) return; @@ -1230,15 +1295,15 @@ void LIVMapper::publish_visual_sub_map(const ros::Publisher &pubSubVisualMap) *sub_pcl_visual_map_pub = *laserCloudFullRes; if (1) { - sensor_msgs::PointCloud2 laserCloudmsg; + sensor_msgs::msg::PointCloud2 laserCloudmsg; pcl::toROSMsg(*sub_pcl_visual_map_pub, laserCloudmsg); - laserCloudmsg.header.stamp = ros::Time::now(); + laserCloudmsg.header.stamp = this->node->get_clock()->now(); laserCloudmsg.header.frame_id = "camera_init"; - pubSubVisualMap.publish(laserCloudmsg); + pubSubVisualMap->publish(laserCloudmsg); } } -void LIVMapper::publish_effect_world(const ros::Publisher &pubLaserCloudEffect, const std::vector &ptpl_list) +void LIVMapper::publish_effect_world(const rclcpp::Publisher::SharedPtr &pubLaserCloudEffect, const std::vector &ptpl_list) { int effect_feat_num = ptpl_list.size(); PointCloudXYZI::Ptr laserCloudWorld(new PointCloudXYZI(effect_feat_num, 1)); @@ -1248,11 +1313,11 @@ void LIVMapper::publish_effect_world(const ros::Publisher &pubLaserCloudEffect, laserCloudWorld->points[i].y = ptpl_list[i].point_w_[1]; laserCloudWorld->points[i].z = ptpl_list[i].point_w_[2]; } - sensor_msgs::PointCloud2 laserCloudFullRes3; + sensor_msgs::msg::PointCloud2 laserCloudFullRes3; pcl::toROSMsg(*laserCloudWorld, laserCloudFullRes3); - laserCloudFullRes3.header.stamp = ros::Time::now(); + laserCloudFullRes3.header.stamp = this->node->get_clock()->now(); laserCloudFullRes3.header.frame_id = "camera_init"; - pubLaserCloudEffect.publish(laserCloudFullRes3); + pubLaserCloudEffect->publish(laserCloudFullRes3); } template void LIVMapper::set_posestamp(T &out) @@ -1266,39 +1331,40 @@ template void LIVMapper::set_posestamp(T &out) out.orientation.w = geoQuat.w; } -void LIVMapper::publish_odometry(const ros::Publisher &pubOdomAftMapped) +void LIVMapper::publish_odometry(const rclcpp::Publisher::SharedPtr &pubOdomAftMapped) { odomAftMapped.header.frame_id = "camera_init"; odomAftMapped.child_frame_id = "aft_mapped"; - odomAftMapped.header.stamp = ros::Time::now(); //.ros::Time()fromSec(last_timestamp_lidar); + odomAftMapped.header.stamp = this->node->get_clock()->now(); //.ros::Time()fromSec(last_timestamp_lidar); set_posestamp(odomAftMapped.pose.pose); - static tf::TransformBroadcaster br; - tf::Transform transform; - tf::Quaternion q; - transform.setOrigin(tf::Vector3(_state.pos_end(0), _state.pos_end(1), _state.pos_end(2))); + static std::shared_ptr br; + br = std::make_shared(this->node); + tf2::Transform transform; + tf2::Quaternion q; + transform.setOrigin(tf2::Vector3(_state.pos_end(0), _state.pos_end(1), _state.pos_end(2))); q.setW(geoQuat.w); q.setX(geoQuat.x); q.setY(geoQuat.y); q.setZ(geoQuat.z); transform.setRotation(q); - br.sendTransform( tf::StampedTransform(transform, odomAftMapped.header.stamp, "camera_init", "aft_mapped") ); - pubOdomAftMapped.publish(odomAftMapped); + br->sendTransform(geometry_msgs::msg::TransformStamped(createTransformStamped(transform, odomAftMapped.header.stamp, "camera_init", "aft_mapped"))); + pubOdomAftMapped->publish(odomAftMapped); } -void LIVMapper::publish_mavros(const ros::Publisher &mavros_pose_publisher) +void LIVMapper::publish_mavros(const rclcpp::Publisher::SharedPtr &mavros_pose_publisher) { - msg_body_pose.header.stamp = ros::Time::now(); + msg_body_pose.header.stamp = this->node->get_clock()->now(); msg_body_pose.header.frame_id = "camera_init"; set_posestamp(msg_body_pose.pose); - mavros_pose_publisher.publish(msg_body_pose); + mavros_pose_publisher->publish(msg_body_pose); } -void LIVMapper::publish_path(const ros::Publisher pubPath) +void LIVMapper::publish_path(const rclcpp::Publisher::SharedPtr &pubPath) { set_posestamp(msg_body_pose.pose); - msg_body_pose.header.stamp = ros::Time::now(); + msg_body_pose.header.stamp = this->node->get_clock()->now(); msg_body_pose.header.frame_id = "camera_init"; path.poses.push_back(msg_body_pose); - pubPath.publish(path); + pubPath->publish(path); } \ No newline at end of file diff --git a/src/frame.cpp b/src/frame.cpp index 2a0b1268..643dd10e 100644 --- a/src/frame.cpp +++ b/src/frame.cpp @@ -10,7 +10,7 @@ This file is subject to the terms and conditions outlined in the 'LICENSE' file, which is included as part of this source code package. */ -#include +#include #include "feature.h" #include "frame.h" #include "visual_point.h" diff --git a/src/main.cpp b/src/main.cpp index 135b3363..61dd592a 100755 --- a/src/main.cpp +++ b/src/main.cpp @@ -2,11 +2,13 @@ int main(int argc, char **argv) { - ros::init(argc, argv, "laserMapping"); - ros::NodeHandle nh; - image_transport::ImageTransport it(nh); - LIVMapper mapper(nh); - mapper.initializeSubscribersAndPublishers(nh, it); - mapper.run(); + rclcpp::init(argc, argv); + rclcpp::NodeOptions options; + rclcpp::Node::SharedPtr nh; + image_transport::ImageTransport it_(nh); + LIVMapper mapper(nh, "laserMapping"); + mapper.initializeSubscribersAndPublishers(nh, it_); + mapper.run(nh); + rclcpp::shutdown(); return 0; } \ No newline at end of file diff --git a/src/preprocess.cpp b/src/preprocess.cpp index 322776b0..3f5745b1 100755 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -51,13 +51,13 @@ void Preprocess::set(bool feat_en, int lid_type, double bld, int pfilt_num) point_filter_num = pfilt_num; } -void Preprocess::process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) +void Preprocess::process(const livox_ros_driver2::msg::CustomMsg::SharedPtr &msg, PointCloudXYZI::Ptr &pcl_out) { avia_handler(msg); *pcl_out = pl_surf; } -void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) +void Preprocess::process(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, PointCloudXYZI::Ptr &pcl_out) { switch (lidar_type) { @@ -87,7 +87,7 @@ void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointClo *pcl_out = pl_surf; } -void Preprocess::avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg) +void Preprocess::avia_handler(const livox_ros_driver2::msg::CustomMsg::SharedPtr &msg) { pl_surf.clear(); pl_corn.clear(); @@ -195,7 +195,7 @@ void Preprocess::avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg) printf("[ Preprocess ] Output point number: %zu \n", pl_surf.points.size()); } -void Preprocess::l515_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) +void Preprocess::l515_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { pl_surf.clear(); pl_corn.clear(); @@ -206,7 +206,7 @@ void Preprocess::l515_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) pl_corn.reserve(plsize); pl_surf.reserve(plsize); - double time_stamp = msg->header.stamp.toSec(); + double time_stamp = stamp2Sec(msg->header.stamp); // cout << "===================================" << endl; // printf("Pt size = %d, N_SCANS = %d\r\n", plsize, N_SCANS); for (int i = 0; i < pl_orig.points.size(); i++) @@ -235,7 +235,7 @@ void Preprocess::l515_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) // pub_func(pl_surf, pub_corn, msg->header.stamp); } -void Preprocess::oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) +void Preprocess::oust64_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { pl_surf.clear(); pl_corn.clear(); @@ -297,7 +297,7 @@ void Preprocess::oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) } else { - double time_stamp = msg->header.stamp.toSec(); + double time_stamp = stamp2Sec(msg->header.stamp); // cout << "===================================" << endl; // printf("Pt size = %d, N_SCANS = %d\r\n", plsize, N_SCANS); for (int i = 0; i < pl_orig.points.size(); i++) @@ -335,7 +335,7 @@ void Preprocess::oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) #define MAX_LINE_NUM 64 -void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) +void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { pl_surf.clear(); pl_corn.clear(); @@ -502,7 +502,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) // pub_func(pl_surf, pub_corn, msg->header.stamp); } -void Preprocess::Pandar128_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) +void Preprocess::Pandar128_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { pl_surf.clear(); @@ -553,7 +553,7 @@ void Preprocess::Pandar128_handler(const sensor_msgs::PointCloud2::ConstPtr &msg // cout << GREEN << "pl_surf.points[31000].timestamp: " << pl_surf.points[31000].curvature << RESET << endl; } -void Preprocess::xt32_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) +void Preprocess::xt32_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { pl_surf.clear(); pl_corn.clear(); @@ -933,11 +933,11 @@ void Preprocess::give_feature(pcl::PointCloud &pl, vector &t } } -void Preprocess::pub_func(PointCloudXYZI &pl, const ros::Time &ct) +void Preprocess::pub_func(PointCloudXYZI &pl, const rclcpp::Time &ct) { pl.height = 1; pl.width = pl.size(); - sensor_msgs::PointCloud2 output; + sensor_msgs::msg::PointCloud2 output; pcl::toROSMsg(pl, output); output.header.frame_id = "livox"; output.header.stamp = ct; diff --git a/src/utils.cpp b/src/utils.cpp new file mode 100644 index 00000000..1e453c82 --- /dev/null +++ b/src/utils.cpp @@ -0,0 +1,19 @@ +// utils.cpp +#include +#include // for int64_t +#include // for std::numeric_limits +#include // for std::out_of_range + +std::vector convertToIntVectorSafe(const std::vector& int64_vector) { + std::vector int_vector; + int_vector.reserve(int64_vector.size()); // 预留空间以提高效率 + + for (int64_t value : int64_vector) { + if (value < std::numeric_limits::min() || value > std::numeric_limits::max()) { + throw std::out_of_range("Value is out of range for int"); + } + int_vector.push_back(static_cast(value)); + } + + return int_vector; +} diff --git a/src/vio.cpp b/src/vio.cpp index 2ff8fd0f..af55c377 100755 --- a/src/vio.cpp +++ b/src/vio.cpp @@ -12,6 +12,7 @@ which is included as part of this source code package. #include "vio.h" +using namespace Eigen; VIOManager::VIOManager() { // downSizeFilter.setLeafSize(0.2, 0.2, 0.2); @@ -250,12 +251,12 @@ void VIOManager::insertPointIntoVoxelMap(VisualPoint *pt_new) } void VIOManager::getWarpMatrixAffineHomography(const vk::AbstractCamera &cam, const V2D &px_ref, const V3D &xyz_ref, const V3D &normal_ref, - const SE3 &T_cur_ref, const int level_ref, Matrix2d &A_cur_ref) + const SE3 &T_cur_ref, const int level_ref, Matrix2d &A_cur_ref) { // create homography matrix const V3D t = T_cur_ref.inverse().translation(); const Eigen::Matrix3d H_cur_ref = - T_cur_ref.rotation_matrix() * (normal_ref.dot(xyz_ref) * Eigen::Matrix3d::Identity() - t * normal_ref.transpose()); + T_cur_ref.rotationMatrix() * (normal_ref.dot(xyz_ref) * Eigen::Matrix3d::Identity() - t * normal_ref.transpose()); // Compute affine warp matrix A_ref_cur using homography projection const int kHalfPatchSize = 4; V3D f_du_ref(cam.cam2world(px_ref + Eigen::Vector2d(kHalfPatchSize, 0) * (1 << level_ref))); @@ -273,7 +274,7 @@ void VIOManager::getWarpMatrixAffineHomography(const vk::AbstractCamera &cam, co } void VIOManager::getWarpMatrixAffine(const vk::AbstractCamera &cam, const Vector2d &px_ref, const Vector3d &f_ref, const double depth_ref, - const SE3 &T_cur_ref, const int level_ref, const int pyramid_level, const int halfpatch_size, + const SE3 &T_cur_ref, const int level_ref, const int pyramid_level, const int halfpatch_size, Matrix2d &A_cur_ref) { // Compute affine warp matrix A_ref_cur @@ -457,7 +458,7 @@ void VIOManager::retrieveFromVisualSparseMap(cv::Mat img, vector & if (pt == nullptr) continue; if (pt->obs_.size() == 0) continue; - V3D norm_vec(new_frame_->T_f_w_.rotation_matrix() * pt->normal_); + V3D norm_vec(new_frame_->T_f_w_.rotationMatrix() * pt->normal_); V3D dir(new_frame_->T_f_w_ * pt->pos_); if (dir[2] < 0) continue; // dir.normalize(); @@ -535,7 +536,7 @@ void VIOManager::retrieveFromVisualSparseMap(cv::Mat img, vector & // sub_map_ray.push_back(pt); // cloud_visual_sub_map // add_sample = true; - V3D norm_vec(new_frame_->T_f_w_.rotation_matrix() * pt->normal_); + V3D norm_vec(new_frame_->T_f_w_.rotationMatrix() * pt->normal_); V3D dir(new_frame_->T_f_w_ * pt->pos_); if (dir[2] < 0) continue; dir.normalize(); @@ -698,7 +699,7 @@ void VIOManager::retrieveFromVisualSparseMap(cv::Mat img, vector & if (normal_en) { - V3D norm_vec = (ref_ftr->T_f_w_.rotation_matrix() * pt->normal_).normalized(); + V3D norm_vec = (ref_ftr->T_f_w_.rotationMatrix() * pt->normal_).normalized(); V3D pf(ref_ftr->T_f_w_ * pt->pos_); // V3D pf_norm = pf.normalized(); @@ -864,7 +865,7 @@ void VIOManager::generateVisualMapPoints(cv::Mat img, vector &pg) pointWithVar pt_var = append_voxel_points[i]; V3D pt = pt_var.point_w; - V3D norm_vec(new_frame_->T_f_w_.rotation_matrix() * pt_var.normal); + V3D norm_vec(new_frame_->T_f_w_.rotationMatrix() * pt_var.normal); V3D dir(new_frame_->T_f_w_ * pt); dir.normalize(); double cos_theta = dir.dot(norm_vec); @@ -935,7 +936,7 @@ void VIOManager::updateVisualMapPoints(cv::Mat img) SE3 pose_ref = last_feature->T_f_w_; SE3 delta_pose = pose_ref * pose_cur.inverse(); double delta_p = delta_pose.translation().norm(); - double delta_theta = (delta_pose.rotation_matrix().trace() > 3.0 - 1e-6) ? 0.0 : std::acos(0.5 * (delta_pose.rotation_matrix().trace() - 1)); + double delta_theta = (delta_pose.rotationMatrix().trace() > 3.0 - 1e-6) ? 0.0 : std::acos(0.5 * (delta_pose.rotationMatrix().trace() - 1)); if (delta_p > 0.5 || delta_theta > 0.3) add_flag = true; // 0.5 || 0.3 // Step 3: pixel distance @@ -1046,7 +1047,7 @@ void VIOManager::updateReferencePatch(const unordered_mapT_f_w_ * pt->pos_; - V3D norm_vec = ref_patch_temp->T_f_w_.rotation_matrix() * pt->normal_; + V3D norm_vec = ref_patch_temp->T_f_w_.rotationMatrix() * pt->normal_; pf.normalize(); double cos_angle = pf.dot(norm_vec); // if(fabs(cos_angle) < 0.86) continue; // 20 degree @@ -1136,7 +1137,7 @@ void VIOManager::projectPatchFromRefToCur(const unordered_mapw2c(pt->pos_)); V2D pc_prior(new_frame_->w2c_prior(pt->pos_)); - V3D norm_vec(ref_ftr->T_f_w_.rotation_matrix() * pt->normal_); + V3D norm_vec(ref_ftr->T_f_w_.rotationMatrix() * pt->normal_); V3D pf(ref_ftr->T_f_w_ * pt->pos_); if (pf.dot(norm_vec) < 0) norm_vec = -norm_vec; @@ -1350,7 +1351,7 @@ void VIOManager::precomputeReferencePatches(int level) double depth((pt->pos_ - pt->ref_patch->pos()).norm()); V3D pf = pt->ref_patch->f_ * depth; V2D pc = pt->ref_patch->px_; - M3D R_ref_w = pt->ref_patch->T_f_w_.rotation_matrix(); + M3D R_ref_w = pt->ref_patch->T_f_w_.rotationMatrix(); computeProjectionJacobian(pf, Jdpi); p_w_hat << SKEW_SYM_MATRX(pt->pos_); @@ -1771,7 +1772,7 @@ void VIOManager::dumpDataForColmap() pinhole_cam->undistortImage(img_rgb, img_rgb_undistort); cv::imwrite(image_path, img_rgb_undistort); - Eigen::Quaterniond q(new_frame_->T_f_w_.rotation_matrix()); + Eigen::Quaterniond q(new_frame_->T_f_w_.rotationMatrix()); Eigen::Vector3d t = new_frame_->T_f_w_.translation(); fout_colmap << cnt << " " << std::fixed << std::setprecision(6) // 保证浮点数精度为6位 diff --git a/src/voxel_map.cpp b/src/voxel_map.cpp index 01923cca..76c3c893 100644 --- a/src/voxel_map.cpp +++ b/src/voxel_map.cpp @@ -11,7 +11,7 @@ which is included as part of this source code package. */ #include "voxel_map.h" - +using namespace Eigen; void calcBodyCov(Eigen::Vector3d &pb, const float range_inc, const float degree_inc, Eigen::Matrix3d &cov) { if (pb[2] == 0) pb[2] = 0.0001; @@ -33,23 +33,39 @@ void calcBodyCov(Eigen::Vector3d &pb, const float range_inc, const float degree_ cov = direction * range_var * direction.transpose() + A * direction_var * A.transpose(); } -void loadVoxelConfig(ros::NodeHandle &nh, VoxelMapConfig &voxel_config) +void loadVoxelConfig(rclcpp::Node::SharedPtr &node, VoxelMapConfig &voxel_config) { - nh.param("publish/pub_plane_en", voxel_config.is_pub_plane_map_, false); - - nh.param("lio/max_layer", voxel_config.max_layer_, 1); - nh.param("lio/voxel_size", voxel_config.max_voxel_size_, 0.5); - nh.param("lio/min_eigen_value", voxel_config.planner_threshold_, 0.01); - nh.param("lio/sigma_num", voxel_config.sigma_num_, 3); - nh.param("lio/beam_err", voxel_config.beam_err_, 0.02); - nh.param("lio/dept_err", voxel_config.dept_err_, 0.05); - nh.param>("lio/layer_init_num", voxel_config.layer_init_num_, vector{5,5,5,5,5}); - nh.param("lio/max_points_num", voxel_config.max_points_num_, 50); - nh.param("lio/max_iterations", voxel_config.max_iterations_, 5); - - nh.param("local_map/map_sliding_en", voxel_config.map_sliding_en, false); - nh.param("local_map/half_map_size", voxel_config.half_map_size, 100); - nh.param("local_map/sliding_thresh", voxel_config.sliding_thresh, 8); + // declare parameter + node->declare_parameter("publish/pub_plane_en", false); + node->declare_parameter("lio/max_layer", 1); + node->declare_parameter("lio/voxel_size", 0.5); + node->declare_parameter("lio/min_eigen_value", 0.01); + node->declare_parameter("lio/sigma_num", 3); + node->declare_parameter("lio/beam_err", 0.02); + node->declare_parameter("lio/dept_err", 0.05); + + // Declaration of parameter of type std::vector won't build, https://github.com/ros2/rclcpp/issues/1585 + node->declare_parameter>("lio/layer_init_num", std::vector{5,5,5,5,5}); + node->declare_parameter("lio/max_points_num", 50); + node->declare_parameter("lio/min_iterations", 5); + node->declare_parameter("local_map/map_sliding_en", false); + node->declare_parameter("local_map/half_map_size", 100); + node->declare_parameter("local_map/sliding_thresh", 8); + + // get parameter + node->get_parameter("publish/pub_plane_en", voxel_config.is_pub_plane_map_); + node->get_parameter("lio/max_layer", voxel_config.max_layer_); + node->get_parameter("lio/voxel_size", voxel_config.max_voxel_size_); + node->get_parameter("lio/min_eigen_value", voxel_config.planner_threshold_); + node->get_parameter("lio/sigma_num", voxel_config.sigma_num_); + node->get_parameter("lio/beam_err", voxel_config.beam_err_); + node->get_parameter("lio/dept_err", voxel_config.dept_err_); + node->get_parameter("lio/layer_init_num", voxel_config.layer_init_num_); + node->get_parameter("lio/max_points_num", voxel_config.max_points_num_); + node->get_parameter("lio/min_iterations", voxel_config.max_iterations_); + node->get_parameter("local_map/map_sliding_en", voxel_config.map_sliding_en); + node->get_parameter("local_map/half_map_size", voxel_config.half_map_size); + node->get_parameter("local_map/sliding_thresh", voxel_config.sliding_thresh); } void VoxelOctoTree::init_plane(const std::vector &points, VoxelPlane *plane) @@ -535,7 +551,7 @@ void VoxelMapManager::BuildVoxelMap() float planer_threshold = config_setting_.planner_threshold_; int max_layer = config_setting_.max_layer_; int max_points_num = config_setting_.max_points_num_; - std::vector layer_init_num = config_setting_.layer_init_num_; + std::vector layer_init_num = convertToIntVectorSafe(config_setting_.layer_init_num_); std::vector input_points; @@ -612,7 +628,7 @@ void VoxelMapManager::UpdateVoxelMap(const std::vector &input_poin float planer_threshold = config_setting_.planner_threshold_; int max_layer = config_setting_.max_layer_; int max_points_num = config_setting_.max_points_num_; - std::vector layer_init_num = config_setting_.layer_init_num_; + std::vector layer_init_num = convertToIntVectorSafe(config_setting_.layer_init_num_); uint plsize = input_points.size(); for (uint i = 0; i < plsize; i++) { @@ -789,9 +805,9 @@ void VoxelMapManager::pubVoxelMap() { double max_trace = 0.25; double pow_num = 0.2; - ros::Rate loop(500); + rclcpp::Rate loop(500); float use_alpha = 0.8; - visualization_msgs::MarkerArray voxel_plane; + visualization_msgs::msg::MarkerArray voxel_plane; voxel_plane.markers.reserve(1000000); std::vector pub_plane_list; for (auto iter = voxel_map_.begin(); iter != voxel_map_.end(); iter++) @@ -813,7 +829,7 @@ void VoxelMapManager::pubVoxelMap() else { alpha = 0; } pubSinglePlane(voxel_plane, "plane", pub_plane_list[i], alpha, plane_rgb); } - voxel_map_pub_.publish(voxel_plane); + voxel_map_pub_->publish(voxel_plane); loop.sleep(); } @@ -834,20 +850,20 @@ void VoxelMapManager::GetUpdatePlane(const VoxelOctoTree *current_octo, const in return; } -void VoxelMapManager::pubSinglePlane(visualization_msgs::MarkerArray &plane_pub, const std::string plane_ns, const VoxelPlane &single_plane, +void VoxelMapManager::pubSinglePlane(visualization_msgs::msg::MarkerArray &plane_pub, const std::string plane_ns, const VoxelPlane &single_plane, const float alpha, const Eigen::Vector3d rgb) { - visualization_msgs::Marker plane; + visualization_msgs::msg::Marker plane; plane.header.frame_id = "camera_init"; - plane.header.stamp = ros::Time(); + plane.header.stamp = rclcpp::Time(); plane.ns = plane_ns; plane.id = single_plane.id_; - plane.type = visualization_msgs::Marker::CYLINDER; - plane.action = visualization_msgs::Marker::ADD; + plane.type = visualization_msgs::msg::Marker::CYLINDER; + plane.action = visualization_msgs::msg::Marker::ADD; plane.pose.position.x = single_plane.center_[0]; plane.pose.position.y = single_plane.center_[1]; plane.pose.position.z = single_plane.center_[2]; - geometry_msgs::Quaternion q; + geometry_msgs::msg::Quaternion q; CalcVectQuation(single_plane.x_normal_, single_plane.y_normal_, single_plane.normal_, q); plane.pose.orientation = q; plane.scale.x = 3 * sqrt(single_plane.max_eigen_value_); @@ -857,12 +873,12 @@ void VoxelMapManager::pubSinglePlane(visualization_msgs::MarkerArray &plane_pub, plane.color.r = rgb(0); plane.color.g = rgb(1); plane.color.b = rgb(2); - plane.lifetime = ros::Duration(); + plane.lifetime = rclcpp::Duration::from_seconds(0.01); plane_pub.markers.push_back(plane); } void VoxelMapManager::CalcVectQuation(const Eigen::Vector3d &x_vec, const Eigen::Vector3d &y_vec, const Eigen::Vector3d &z_vec, - geometry_msgs::Quaternion &q) + geometry_msgs::msg::Quaternion &q) { Eigen::Matrix3d rot; rot << x_vec(0), x_vec(1), x_vec(2), y_vec(0), y_vec(1), y_vec(2), z_vec(0), z_vec(1), z_vec(2); From 48094cb5180d3aade48dd686afb0803d83ec5960 Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Mon, 24 Feb 2025 00:37:50 +0800 Subject: [PATCH 04/21] bug: add normalized to avoid Rcw is not orthogonal --- src/vio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/vio.cpp b/src/vio.cpp index af55c377..6e14fcfc 100755 --- a/src/vio.cpp +++ b/src/vio.cpp @@ -1694,7 +1694,7 @@ void VIOManager::updateFrameState(StatesGroup state) V3D Pwi(state.pos_end); Rcw = Rci * Rwi.transpose(); Pcw = -Rci * Rwi.transpose() * Pwi + Pci; - new_frame_->T_f_w_ = SE3(Rcw, Pcw); + new_frame_->T_f_w_ = SE3(Eigen::Quaterniond(Rcw).normalized().toRotationMatrix(), Pcw); // avoid R is not orthogonal } void VIOManager::plotTrackedPoints() From 38711df9abb6cba58ea1707d746a167e7396571b Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Mon, 24 Feb 2025 20:43:33 +0800 Subject: [PATCH 05/21] feat: migrate launch .xml to launch.py --- launch/mapping_aviz.launch.py | 117 ++++++++++++++++++++++++++++++++++ 1 file changed, 117 insertions(+) create mode 100644 launch/mapping_aviz.launch.py diff --git a/launch/mapping_aviz.launch.py b/launch/mapping_aviz.launch.py new file mode 100644 index 00000000..d9488b03 --- /dev/null +++ b/launch/mapping_aviz.launch.py @@ -0,0 +1,117 @@ +#!/usr/bin/python3 +# -- coding: utf-8 --** + +import os +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from ament_index_python.packages import get_package_share_directory +from launch_ros.actions import Node + +def generate_launch_description(): + + # Find path + config_file_dir = os.path.join(get_package_share_directory("fast_livo"), "config") + rviz_config_file = os.path.join(get_package_share_directory("fast_livo"), "rviz_cfg", "fast_livo2.rviz") + + #Load parameters + avia_config_cmd = os.path.join(config_file_dir, "avia.yaml") + camera_config_cmd = os.path.join(config_file_dir, "camera_pinhole.yaml") + + # Param use_rviz + use_rviz_arg = DeclareLaunchArgument( + "use_rviz", + default_value="False", + description="Whether to launch Rviz2", + ) + + avia_config_arg = DeclareLaunchArgument( + 'avia_params_file', + default_value=avia_config_cmd, + description='Full path to the ROS2 parameters file to use for fast_livo2 nodes', + ) + + camera_config_arg = DeclareLaunchArgument( + 'camera_params_file', + default_value=camera_config_cmd, + description='Full path to the ROS2 parameters file to use for vikit_ros nodes', + ) + + # https://github.com/ros-navigation/navigation2/blob/1c68c212db01f9f75fcb8263a0fbb5dfa711bdea/nav2_bringup/launch/navigation_launch.py#L40 + use_respawn_arg = DeclareLaunchArgument( + 'use_respawn', + default_value='True', + description='Whether to respawn if a node crashes. Applied when composition is disabled.') + + avia_params_file = LaunchConfiguration('avia_params_file') + camera_params_file = LaunchConfiguration('camera_params_file') + use_respawn = LaunchConfiguration('use_respawn') + + return LaunchDescription([ + use_rviz_arg, + avia_config_arg, + camera_config_arg, + use_respawn_arg, + + # play ros2 bag + # ExecuteProcess( + # cmd=[['ros2 bag play ', '~/datasets/Retail_Street ', '--clock ', "-l"]], + # shell=True + # ), + + # use parameter_blackboard as global parameters server and load camera params + # Node( + # package='demo_nodes_cpp', + # executable='parameter_blackboard', + # name='parameter_blackboard', + # # namespace='laserMapping', + # parameters=[ + # camera_params_file + # ], + # output='screen' + # ), + + # republish compressed image to raw image + # https://robotics.stackexchange.com/questions/110939/how-do-i-remap-compressed-video-to-raw-video-in-ros2 + # ros2 run image_transport republish compressed raw --ros-args --remap in:=/left_camera/image --remap out:=/left_camera/image + Node( + package="image_transport", + executable="republish", + name="republish", + arguments=[ # Array of strings/parametric arguments that will end up in process's argv + 'compressed', + 'raw', + ], + remappings=[ + ("in", "/left_camera/image"), + ("out", "/left_camera/image") + ], + output="screen", + respawn=use_respawn, + ), + + Node( + package="fast_livo", + executable="fastlivo_mapping", + name="laserMapping", + parameters=[ + avia_params_file, + ], + # https://docs.ros.org/en/humble/How-To-Guides/Getting-Backtraces-in-ROS-2.html + prefix=[ + # ("gdb -ex run --args"), + # ("valgrind --tool=memcheck --leak-check=full --show-reachable=yes --undef-value-errors=yes --track-fds=yes") + ], + output="screen" + ), + + Node( + condition=IfCondition(LaunchConfiguration("use_rviz")), + package="rviz2", + executable="rviz2", + name="rviz2", + arguments=["-d", rviz_config_file], + output="screen" + ), + ]) From e34adaabb91b8e2c1d3f9b28853d14d8c15ce583 Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Mon, 24 Feb 2025 20:59:22 +0800 Subject: [PATCH 06/21] img: add some image --- pics/debug_error.png | Bin 0 -> 146534 bytes pics/rosgraph.png | Bin 0 -> 125820 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 pics/debug_error.png create mode 100644 pics/rosgraph.png diff --git a/pics/debug_error.png b/pics/debug_error.png new file mode 100644 index 0000000000000000000000000000000000000000..3baa5215bfaf7909bcd9a2b764abe11f45330f4e GIT binary patch literal 146534 zcmbrlWmH_t7A}fIa0mp41QJMa3ob!|y9D>(?(V@YxO;G?fyP}zkjCAu@y109)s&iZe)Uy#n1Y-*1}ZTs3=9m0q=cvv3=HBY7#KJp3KH~=D91J) z^aH_BSW*QA+PqM{hC=@*a{8?9q-<;AjZ)C5P){# zH&;=25^*p#a5A^Gd97k@Z4A8$1H;P9`ft-)m;( zo#X}z5@1BYTLR=%0qFR}+-? zne5XYKrkqe@=tr0ENEaFic2SfzeZNCaTcip-{6sdS)tQV%*WV zycxW$=~huGKMh-+>>acN3xJPX7ma_$3*E{VTsL)rEvmX-Nm{u|u6oVhv7TFXGMU{8 z$PrdR%=tTV5KWOgkK;?9op;!ms)2fEFUjv-`rM)N1JH!LF@mm(IE(+j6EEv<=j7s* zi^=2S;>h9wz-D!E)u#r${aN=0Rq))gXUN<39`BF!W4pn0--l)AQgu+$PCclGSoO|` z{dSyA^M-{A2b z8d(>u{?asvT}9;tZ^%|8m9)A-0g*_J++PcUwol zJFe`1g&P?3bRKc>%$)bm6Y80 z$cHvh8~MoPHMO;u@CTyFBIM=dR?uYDRIvB^uR|e`Ym>tlu3y}VQ6aX!b}I%n%P81_aPHYcpoZ(IgqKyR9yQfU~yr;}ZNJK5jgKc!Go zO6u1-JTm5?l$4Yvg4bvX_Eh``>!yiu6U2I#{{|;`;h|!6XhI7FD(56I4aw$sO-lHs z$zgkDx>VJ2=hRI&K0e;QNgFCOJ)OK`YWSZyCcy%rM;ofO_<S zsGYK8!)b1A{w*X#4HFBC$@^?;@K@)CmF`BF>(`woLC3yqn5k7Xa$|yjT-#QvS~df9 zd!C|_l9G)j{$ID@{@ixJ!N$hkv*VJGkU&A=*gC=W4QT=shVD?qTyi|{w-`X6Q^7+> zNT`iYwbaSj!J)R&?(HA*oiS~=w7kH=s>=BOUEi@uTg&gI8x|*E^gJxN<8hS0(G%az zmj4rU9;|eaM`B;BK($eomzBNL$Qat@;U_RNU_*!RVXj_0nmcN;M*1yPY+Sr?LITfr zcXCFCOufal#qnItrtX^R=(kKF0{&ka44N64oF+ThLEp|CU+u7y3OL?qP``g)96e%E zc4#>&Uo;ukv;LZuHLkPs6MDWKZn`i$_6ELI`rtxHzPwk&8#v@7^J%kE~h>|4x%XJ2WH*S*4^h&mbG8ZYVEa zgvCTfEyEw~9FDzY@{QkaLe~IDR}J$`rA%hztT0A88SCq>y<6efacHWZw}PgTt=xnF zsBQd5OnSB*@U<|0TVIJaA%Q;s$JB>sIhU3;+_3~U0##6>d%DF-Ch3lCYM2q8839Y! zc^$$J-J7Qf9*f08+j&lV6HW9jYl)0HniOKc?LDaYN4&3uVuT9h5RE+G$)p-%YJTe| z>^{TIu#Lc2ZLq;y+sO4ARDSe}w5V4fM#SIz7USvt2MsaF5%L;Ao)Xn-&!l)$NE`xfb92PDME{jmwzT$RPQLoMAuR$Jv- zi8h%wXCYh_yFzT#w5Jebm}EXqslZ~wea`fuUH{#|OqI#_6joDJ;excNs6&xygW!!kAVSq{YPb%7XBgG(4aRQ%MqF?RgF+8@ba~kk(4w5k7l-BuXr9V)R(=M z{s&VH5&#TeYI3|6DXt)5Ao<2>FFu?q86l;*xxjn8S&3O;t_h?ymeP2e$@Me(Qabg# zgW}eDog5eSnX=S}t-IxtCrH1aKZp=MnRaTfp)b6r*pXZOX$6_nTV>x$R8?Az49bSgdRQ;ieVF2L zfaVhI_luEHQ4H1A_;q=uAa+?ka>%M;ttTVJr7`DW+b4&gAgHBj-5pPZ``@?Dh8d-^pa~lVjD? z)W~EDWb!!g<82*7gKSG!{|k8MjnT~+aGqYbKIzgji3L*R&ravcyE$WJIN40$-WdF1 z&iv^?d&YL5Gn-1w!9yWNBWtHk{PgmouUr=pE?D#sLI5!rHHYsM$_!~Y+U}1ke>8e8 z8wd-a)DgIe#~_(KS)7zbabVxc62ck>tbRH!_uRiW0|+DQ-X0qBB(IM2=6btb0gY6w zy=nOG_&Ti_7%8m}*r}h|15XY@&eo+l6-Q6JN!559N?9DW5;hCfe83=8OZ7)Eo`7$| z%a3quf)KFFVe;uk0*2K>U0A)IYfbh+C9h0+6Scj~ z?;s~vQgv>-&h1%uG-b1u#+S9XGSA!6D|_}tus+lJ*fUT)cB0rr7Z?F?F=&AdLJ8psni)r+djWJ0)Tgw zXx@8^aM0>KBTzix_MO!qsJA%@D0lcKam1z)k4SsoR+gc=Mr)1q%O0e1AEF-mX*>#1 zS1$hiRg;MVkJ1u^^~L(@+HEzoJ(`V5iKkIB)v$B1kxCbtMo^DMSfVO%F_=#RY zI6mDa5pak|NIR{Dm=7gYvgsVUwtYI;1DgiNOHJtHd?|}IEk_rdP`?|VtaZ_AH;$S9 zGihoMZc}wI_ki6QPNfR%2Hd2WxVX3vnw)RmAiN;gzaQOEw=U=&aowH`wrT$!_J2vgj z2M{&3(FEFtzO^1QjlB8FFjzNOJC0rHZS|frS#WgNK>oZVVrBh+hH1d%D~2OYcFva; zlBRNZ_6}E%IK|wKGmnsgMo0v=SL4uty_-WN%hAOtf?|mWw_Juq|9jsT49y*bT=y@I zJ*meBc*c<&FnDka#TECLXT@<&?hlbODt552POoo^<>Ct?2)(3I3Grlv4p zf<0IL;*xYyUHRI97=h3&n#t(2W;BuzV)P7k%T}pc)#%mHqNBF$VuSTmv0^?7E$yug z;G`004VXV`i;B}-tuvp5A!PlE0s}=4Z$yHbT@KZKo*%Ef%d5tGDj0skOl1#^6Qtdq zgOfvT7NEX%AU`G5H(b?n^Q<5V=?SL0Ng~xV{L-4}vuuI87G|;lSa!Ercu~514f`?# zxKXQ%I~=__2xRh>Nv8;QFos~=GJXhPHBZ0UEjYE3L9BfeAaP&-Iv0o5Uy2Cm zsDvOF>4+)pORel)Vy{xPC(tmq_%|oRWaSUv8Iz0HwkBFumi!tZn#?fe#&o@{jQm;B zKXozNjCI=617x-+NVm`tTq`1|Dq3LBF~59bH3`}ADtBa!?rMv#y1&huoIq&_c(Uam zO@t-Ke17`SaeS%&r7cmsS*7QgyZ1S3zaQ;&m9It zLLgaYPn=sWE4l|ffI&{4iH#AM?jbQ;r3QYg4)0*gGR}PS&+!#F1dfUy;OUGJDK7Rv zG2=EeEo9oM7Qb@aMt9zL3{tu@rjO^?7!e~q$~c_&C$M(XuYRLrbUBgF7fS%ThiX01 zkVtXbR;Zt^v)C(qfsJUJ-^G_ z{bdb(itqM3oTMstZr>Guu9f1TO*MaP(DKgly!E}F!oF6s5=5Xw58*+5p>rYf{J2QK$#Du#}i zTOxAu4sVImGShPxf<|Vs56^@4hY~Y*R6JTJy(;l_vzL@n`EN1=eV_L9XjoSX{y}gI zLz`VjuwpR&umbJ0&rWgYVVTYK;`~Yq0 z0k}UHg_zvcm;mx0^qfN-3~a8fGlw0I(j1p{0&lw-0VDL-&U#9!fH8FPFY;MH3a$WSF4P@z80jQ*PoGXG!VU=>AJ#gDmNxv zT&2L)+l~1t_dC|>b0#csPZjom>Qn(KSUnGU*n-_gd*y)O-E709l~g@5m8QM;{ja$f zYjIjUjs-oPQcK;1{5G9G9!5Yc8#ARJy^4+=oGtm0|p3x$JFoggdAU><&tiyWKfW*-ceqzsXUNKA)zn|b?| z$5bdPyWAF6oSH3BE&}X4WN=s$Lt4)9xD@h zB&#*i-LP!J`Qdt5a`w8>-T7)2`H%TcCi~}Xth13Wfa}4NCxK@MwHjx0Ms1k#jr|$y z!t!huc%V%#-`OQijid8RdbE7I=)GlCS3AVhMw^d z6v7wZ(~r{14@=QavD=oodsEHmWa6N_`5KjgxThRQrqP^23A`&Xyt7w!Y&+&`eoLH< zc59acGy$F*^kM_@+Bz4@fPp4sw-syyYiIZBR#Tp4C^0Kv;M2=cJ;C&*!Zu6+U%%w) z3{WGi87@c8yQPbbF1JB470dDbhU*&+2*hh~Hctc)kc*k$3Wf zQQe>Glv?Y2+EgEP%RZ`S4ACIePB&$_hOF>u_XK-_D4&+x6LyO`B-$$96@;4ZMGA)1 zIL!GTYl?}AqWVqlZOxlzZ;x=U{tya8dU!YoSuHo?``uk0Ox9bfL9?55Dy#ACY!wBC z_l083j27+=j4YH$U}v8KpWl`+KpQyG;k&Z;nlG=Z>f9xiHGskqQ0h6Gk=z)GZENgc zJk342B3h1sZ*BiDQGuSG?HL>0fjhoKDYyt)j<)pRe4~8=6lWAX>f16(w|{L&@r+Sa8fp`EF8Yt%NkRcL8X_c+%xbmUUeg-_|)-cjmh0XB>{O&D-3@ zw5v4f&w$r0BL7M6e5;=2Q-&wf0?ZY9EGw2F4x@QCnY>CojD*)RqrZ0 z*Z}jsm0IG^$UF&IhvNaDFDsicHEU8Z(jHW%r{$4Mh) zqYJQI6$l6nbkvrIF6V#bAad*u%&zju1%4~=Iy*#@QFlQwwI@*BMen9n>vK7TVUc^i zhTH6WMg`I(>CFN`Hm|NZjd=-7yO>KZcYRaYt6?j*^LHOkutc-fW)ZP*V$T(AY9p82 z9!>|E?vGoDxE5b%Oib90%1F}``B1vR9?Njb-%Ut$*xDD;6wj`Do=?KFmkC2~(vrWmzI|}`hck?8 zcISgf4mmrvQW~VUyz!0dU!Qx$+T=tUyM;t9Hl`Ar7g(qCSgx=#G zR*b3XgvuT#*0&`_;4UqujNbblr*Vz@s{Blm~@@ULuw&_~zT*WEEswHXPZ6h{z;Yr+1IZql2RQF>_t z)8HW=eVvXI8-q8JHK4^1@ zj*I(;%10CKx3fwg3GP|%Gyxb8A_W_)xwP1~EJHU#@U@VB+=a{6Amy=~u5{M}dk=D&UM zK3IW2!|Xfpgh45_24X`)L%WvcJLcaUvqbd2z53<}2ni(&4JrTGO@T6~*w_lYI{8qV zsHCK%x33SnUu4fk8q_TK+a67Jzgc&sl+g&7sakqcOk~F7hZe8 z3!EnX5C8YC@aMNX;^N}ME!6&N{(r8YaFB8mH-sbp=bl4W1Y_Q#8A|JKF+xMNtMUG_ z@1Z{trD2Qz=c{l|n2%IV8-ra-)6C4zi?!1^N9R3z(;T?)ohZ3N*FxytKNK-vW+Ewe zK(LQHN-s)g|85WeM9jZ|Q^+S}5clmF0If>25#!u4_39>L1~xnDw5?sh)Uii-@(t_E zs`Vr-A6RV{&zG{nKi{Mk*}l)m{!7Gf!70hW7Dw&JL>s6;UT*FIzkceZ7h zU|pK1sAwGD?=#p`#ae6A{?+`QL=8fY$@Zd~hp2Mi0H(pkMSdTFkBP+Mz?P55?d?}- zate1g<0*{)48!wo*Y3|*fPXmCtpEjd=#Xjro(|Rv=mKOdu`0G@b94?P-(7D#CTWxU ztPJM6KFfsPMLtHwN!0DF5TDZ@P%zqLuFP%kUQ<-+_D{rHlyqIp`xs0gEFGD7uQ!r3n+_2zM8`JzPQBVZU=>3+YtObcO&G}r{Nz*}Q+)rL zKonJZ966^U!fd_<^OUWyntkT1Rv1NA?>6o_WEwmMW;(m5Xmh_CG=IxsEer5?vv=+( zHnG#jza&DrKKRYy7prE89zt1la5L-X9_ud*{<;&D$I@|4vRgvq=@W-GjDPIX`mx;nh4Zil(C&HJSmRmARm{7Y0;}4o zJ-yI7JzJM1(D63L>tVi5nO_!c-J@tr3{QU0OEXF1@b+NteyhT2#c=GbR&$OkwX!$j-wYFh<zl6#zN$g ze7nugsi+xvL@nH?Xwx#-tX9frLcdr?<4~wXnY2;ln+CQ$I4!bAXHOzdy*}(8twUY> zbq&Zv%R&A(N8kaW3fTkh({0u7ddn_I79!t)D&Df3PeM`O$}>*DDxq9ea=(M8J|*%j zDMIJj*WS3Wa`N#AnkOQu4gt{V)flr?i9P9ZLmUzB1o%~b+#Jvf(X)AZu&m>fx|0l) z+mUy(HOk`E@jliOK}RfRozrNPaFl{~`dRs(VEw0U34dQkNE9n9=qg!1L(-S-upM#& zz(-#gf4X}d9>PjTn6>dTndB(F&g`7E)#;uPr&tTh#x&vGT54^i$*v;nJq^)18-B~Q zZtRn~ZT|S=8rl8`1F3UQ&~u^tH{pJev5a@A{0H*Dm?jm_J+`CSnKrvmB!9W{rh61C z+|~%sMSky>?!6gu@=&11;<3aTd2zAUr^i~kOD^$fgJoyF?{Y;U*&SIf83F5Uj`y+; zfEI_^jt9WyjLht`y#B$m=Wp;(dh)MY0g5uP@Ab)yPRFwN?AHt|tOe~&Mr8r$1i<6o z9w7hcf>4;H)8}f}TPNKXBYH)!+)}DiL3ILZ0;4G zO`CP6<3Vc8;Vl^f#@`(0WoH#w_~M$$sr4@j|L9PB4&sFkwVTz;qyb2sdp=qrPp-P{rc09kjSd`1#tb5tEeW)nHlx-7IPam_~UEAY(c53vIwQUcRwqdU)bd`qfaZKz>mNqEhNZI}Q z^lr=MZjiLW2wFq7U&v^8Bz&f6s6CrQ^~t_{#jlwxs2m}9@O6TDuKysGqZ#RjJnzt( zEbs)mAHZkN8==-J-Z4O7JohYSXEamu*g))byJbmTsWTjquceL;$SQVTWyzC=7e@C5 z#@CE~p~fr=#EAd7qE}6s4?aJQ+529y=~(b7-Xp0m5)aLmyHxSXM2ueR=L7U9?*FB=sSWqv3&&agM{oX8IvRliHwlX7l6CoJVe~-^l8R8@@Nzn38cQx+LY` z7ysJz5H1|BiabzQU!^f^@xGzw?#{WtwKm4+l#z6Oo7shIOJ&MR>1mYn_ADaZPTYHF zR=y3iLN$n>QZDy1E7JL4eZVDBzf{kYp+3g94*Wb=3I@Oj|=qzma*p^gq5R=UVo}4)a?WH23@AIO^ zW!f~{-F#AK(Mq|!ijd*8i+oEJ=W&f?coIVKy{?T7!X${Fy7SN;GIo*3h47~5lJ$)emk#amA3Dw$nS*l!R9l$U)pxS38_Txe2a3*$1bslhQ0^esrLe@ zb;)&kj5`6z-J>NPtey?YPv2nG#tsrkzcIR{dbT_zixkDDziV3j%n0QO8e{v;)xM*a zr*+`($mfCAk0V31&19H7wJQpi~rPH0|3eoSqUz9tdV~*op zTK6`@>Aa+7E{bdxe)l$0`y$j;;0c_0G-(r)?P|}LNdO#lV z`}Df+jQ_ewqn+s5_X1zgM)OyI$WUtgS1yJCbhrSxhn1){1EYOpF@VDgW44gxe^e>m z><%{=k2w#ka(rpc1c2q(Us?`Zcpmi1vb?A{-B+R!laSG=(&NXnozJ>>;yH+YWY%_NoDEr; zbN3-NS)h!Cu_F?=E*hUeJOFWyR=HrIWMf3hzbT8LJNxJdb%DMCwwEG)_vGRj`U`4D ziUARu;;(G2&)93l()oo2bGIX&Ufkx0S{&9!=e4q=a)UYwyDRna-d|LSKUQs>_hf^w z*_pym8et?fN10ZS^CtMO?UZNl_tXs-I=q?&U8@v(a?&uO8yTu#i+kA3i1iiZo`Zka zp$uTS8|D}cBjlV=R*AFP$d@mx+CqE0jmcGww-*vW)rr!DCVv-NCTzJ(A7{W2#z*dl&fNa(MZ zB{`qVFn8jzQhMX{qNmC&48Q5;YVEQdv0r-60TB0~DWjINwNu{m7%buNfmUU?Tk8^; zl^3VeFk&)K`9nOCq|J=Ua)%{>7AKFntGwRv{0Y1z7PV0@XO5x%aU3UTW$=Oh5l7d1 z9X`u3hRUKUvy`FPp$Q(-xI7`<5gw&F{Q~Rb3)iOGw_QB^*=2g+XN@p+fXy<9#^Vhd zI)%}9R%2}C>$~GcqAlhUTXlLnkMy+89P5-QOb)KBjU9}t{|VGQj89S6!nAr)EjHI< zK##Yu<}}=OHXrm>p2_t_Q3NRwkG=c->O66&}A`IWywj)2f*eZYqBsaw^je-)bvMU2=U- zArr+-r+#KiRy~($V(BK@to3)JNjP6F3@uH zLvNnW_!znM%;#O!{&-}B#mpP7b%b$}=C^h>#VI(wT`Tez=Z7zY-q-iUv~@Ui*Gq;|!iWD5zN?Px;yP5m~-|Zto4G ziJSBFu#H{K3yu&;hMvqlL)E7`9Yu1ryHez*wRDR6Q~N5nc3NY(#AV;bC>iNMW$z30&Lp4Jq&*X4(!C+Si~H1M3XT_*%Z=Fk z$#I?K-QJU6=969QN{GPGp*|Dm!2?=9a$_=?%vnLZ@wwP121UmGB|8cMm$|+s0c-ow?r- z!NJ&iV$`|wWyZen&Ty?$!K&;35R@isg|jwtpZO4UMQa_|r$>MsB;LYSOEKw?NiRKo z0b96|)gxF&+2zqED#?`CkLD~nOi_k;ZZ1Mfl|T~!kv4(Z#4no~%JH6dxQdUQs8@}Q zST*DPFiF&n8v9faR=9?nPcU;yhwE5D*}t(Lm;rh~9h}M_Y18j1L)(PL^MEkSs=d_w z5^MDeFOd??Zs56RWqZ>7D7r>;+v4!bLaiZ6uqXuGJo--)WQVHqr-f@PV)%2S9ijZWAu1Z4`hO5f__i<>Vh(-rflXxw z`cFXPGNDCq$Yh!IR!Pmh7z#!+mf+0O3@w)`Kw`d0*(mzMre#)pZlv&E zIx7}Uf(0>$qg0S5Sg{R0Wu}GGR)#yE$PE?t+NV%pDqT?#dhogo*w`l4U|;fE%h1q- z*L}EtX^FO*dpNRTD$OJ4O_Sx=$QCw`I{Ee^3R`23gudMa^YVaRy zfhSm%q{_5!^cJ&2^`ZC+c9sPQ@4l1aJG7vKXkPOC<`4woXdEVgS2igAP@2nNnC z_Ypna6ZU?^9PpA(Kp}t}Fh9145 z_>wJ>-SKl0c(t=fQxrQ__i$odYPdiOZFul_;ld5(2(j15F(e>3kjygh_rN% z8;|+%2S_b{FKLlk_3soxl^J(csGHrHXs$lEXZYdnzVLryB|BIIF^7;AUgODGma^sU zN7rQIN9kpv%RL{y&WT%_v@2^Lk4*H@ZNals(@D8Y_Dmp#c$+!8Tlvdune3mjD!KQv?$WF_3mBCZ_yB~069KjCT!RvL+0&x^BWIb9_e<);1%Am4cPd}t! zY+U_V!t~vbcy*jsGLM~RUq%<5X&)}SzW~YWtwZLk9~6#-r9iMVjJ%;0KHe5?5kCB< zy?q)8A<$6__{6UrnY(hFQYV^g|I(fkEFbP**gyJzV-KumU0-pv`7b1q&6XVM4)izQ z;m~C7WbUkOz5dBAf`ax@B3k~v9~ztcNn_Vf=cvCtqmlxY6LLN>9QaZ^T_@nLo8uOfU&>Wfhe5{iddO;|E^a3|+7+vWS2lfbkRA zJ5V22zBLr45FmPZkv|fXQn!m;vL01z<}h0A4$!31tmhW^A4Om=82BtI1%v&uSRkkarqvqJj?$HkXSS!mzOHUsYysh z!9yf|43F&$lOvd16Unf9*KACJR=CU}w#Vf9GdL7O$q$#}p2z+=_j=npdZ)AD3 zyI>Dc*bK78w|+~$HBKtJykBLxyMk|>+)?zIuYmbWs{UZEkX>lPbc2(C&(KJ!ytrrV z%-q|N)YII%uDBpcO)~uuOr8T{a}`C=eV**ow`;%3JTVza;5*ou=lS}wg}<|)WO3g2 z?F+VAY6hf>0!0}-5TgX`jnc5x60-|j)pC6Q59Hv}vhM#;OAMOs{G22EL_E)W{Xiv_ZKVQQE>cCx7SRne7)9k+l(F zUbsJ2#ECU5{8w91Ms?IrXaP9CjN7u;=i6n&?UklU=PbsqZr3j?NK%hlkty8`|JDP0 zwKFDs(Z_a?#^=(BJFnj*=BwgAtoR+1oRR7V=FHn;ec26{9p9N?zdWWNYlQ3CK69aI<10-?Ifnk{VtewMQ{_=+RgpB;lkI|wVK+6Cq^$96!_m- zpnVh0P-bWSlp(%fm!mWCYKhzFh523#Nv!MHdYJX_{V67GM&)SNv{7>PA+ROv{l*33 z+Eop`^qf64`%kC)gP)#DZn>^*Y*LQy&%hgxbBiRh=ZKQ?m5uhDrbFYM#&FXHo6CjZ zGER)5FsjMpUrt}=fbtVJb5*U*^741f=cE+AIDJ=CS#WwZ;tkU7Uk8)uKiY1!c?vr? zUOd(3t{z!oYqwxvMLvZxJ!$p^1nSwj8bcsr`hm!VEsk__1eZl(I~irKS0*Q|RD7M# z^F5H6D_m_?QXIaqF<2?pK!D|3Pq0U=K5{a&m(N+-z8yjl^c{W(OAoKmT^#q;!Q43UjgNw-J3I<+BXTvltM(gcmiDXWv*m2pAt zzuD;r0$n@KV&z-IXwvP*+2?QRqE24nPe=J~#wO+0L!9_H;3dwcj@yA0q;F0>VW1F_ zNXP~2xlxzH08SGq{lmsFowJH0a(Ev(OK&D z7BG1sa+dk~d>J~V2QUk*IDZWc&|SDOl-da)V+O`rVI-0C^0WF!7jJlsVeBo3x|8>c8VW zeC(FnxB$%M`$!~yuSUKFzJ=6qPY>~!yp5tD6YW@;9j|sF;u}xDIiDPlymkA?k`$P< z`HHRZ7q3(EV-Y~a@B3&gz!ah8x_)Q6X_QpDW&;c0Ib_iJ`XOADerPSbf_KiHby95d z9Bsf^ewHAl?4PiOWcoeZA7ubE5KcTiZd=ol+Xv@Ew`aWf{Nw zMm&E}cfM5&oj32c?M~2OkGWPEp8+Nf&2{;k{bf$K=a!1M#tHb^5z$O-o%z=s`4$qa zAx{f2J(%N7?i7d4P3MC%C-?fn9UPhJXi1e0%HGRn&DYHdCHW18s(ZZ$=i-xg$1g8D z=)+&WBHUg)J?p-1e259zyFGNkEf>YC&>F~{JW>rN5$Fh^e)f{?0Pke;Fb=5l0oF;5 zTXt1I^~8?AF?bl7gY1@60g8vHqMVsiKqgD~3#Oy>pM@U}mk#+ahELm0@-dd5%Ha`o zFA;3pNC!b=wnlj|9&(Ax83P^OX(y+T?)kse#q<(euBV=({r|v7LJk+I6@kKefP|z( zcP;PeZOBg)JAFr**bMXhtT}iqy^f%_`Uj;LV`gvin;VMy?-%FxfLT<)KuNLZB zOK8QPcq32apSlsPR#}6QfZjtNXTJ<^xJLLwN(3)&09C^wg#W>oxtpeKjRiC4?Wbi1 zzhMHS6?o6do6#l8Go+*o>qIoBR5u)b;|$!f6~FF0e}5~@H=fH$_3W6?PbIiLou$fr zYIis$sL())L#Yq@f*#DB^I(%IwPo(`_pL%oa;2&lHY_8hl{=AjD!_~H!nHJdrngbx0LKPxPkvIu}YK~Q7kEQr(#tNG6 z0+hjGmYUoN^DN1F)g`++YVx$MI;?q#54yClyHYR%@E!F>7cM8Mxm_(|n8KZEw-)&T zbVP@uokO!(f(mNf59D^kWv*S3SjmEH+xFjaXP!4W4Rv+h@0pDeTp0D7(|- zrv|Z>4zlf_@&FkWtAsgl1a7)UZWP6I-&9M=`;@4po@E7+F6o`{=P&UlvwHucRPtBV zqH40}VXkZu2*~c>jx{HAK;r=1S+!W3i#O67T`;Jc z$ddewF>SN{)G}22RB#-5=Ojq3zvsm%d(Tm1#TY$MuHerq#&?jXjAE@5#cC|A$W0km z5E9RvmQ)mp5#2(+K@e$jLz2w0etAu(`}}qm_?&)vBw%0^2aNhsILW5-p<^GuUp|bx zOh@i;MZ_vqJtHZ8&bwuLY%B zQ)@X$(7HHD|IOs+jxoC}e)l*&;KpFd@QM^@ubAx5cirWS!aW~`0 zuiNfJEzZwTTBc^@_2(=Ac#r?`9HHjVipX?05Ca`vsD=QSDG=V>In8%{vF zu7oh;_3JhX#nK$FVn4h@YO+1b3DssL(M~ue#1d3gN?J0NaHsE-FW&lp%fc4MMcEr1 z9ljP9MyZzMNceUp06t88=b74cJ$ksD>1s4OY{vArhTn{U{{DA3Es-uWETCn4}Y2%vtyj_cu~*+0Qv zl|rYQ9}vMye(vh1zjD+;XTm$>h&WhAe3RAj(>cZv&&hEBpdouGbH#3!k$yS;`J~w+ zOIjnf|J28U!XqrlERpq=Pa(A0oP2V4=(B@9qpd7Y+wTw8m zIF>{Paq~(188UPqi7qU(_V|VK9m>R$A<5Rc?c>>(C(kAbY?S-U zWGcpjT`+Lxr#ICYcgA+LwGK1{?_Y|PJt7oy;a3iq_4J<)=6&W8tJ{jmWEtEZ+|pi3 z(jYU*5VIeYZ`bA_0G699j@qHGU6j1Q^Yn)2U!3l7UlucL(=}fER{C%+DSf2}It&NA z6HK+U>*`y1P0b43nBSYGq6(WBnQQuzFFC31@@x(&gQ$ExLgbAMB@r!X@;h417(Gs( zR8+yII;MTDAndCi9DvZ>q^&rcN%IfntZC;U1nE>&yN>h7&8g;x?MTgYKostaHmzE| zUv)QBWKH_&ece_E(tZq2=fucZ)+sAZL3kQz3v~ zp2-^o1Cb_$h%u8rVWi|akgE}L4M-68oh$rZ6{$yyYmq@te$EPHZVk`F>^)8}i90G+ zzFDkx8~S_lEr#7l`y*l;^V;H9C6Y(sE~1|`-#>mqqaD6Sf~2%uo8@`6aJn;Y$eY*< zb@f$Pm4JD7dl4T8`eSI68wO+8JzHq?j+VsZFu>hOJazA)ViUggDV&};h`-@x4tXUk zQ624_wbWRW!|onJ9dxd*S(n})p%iY>&{K|XsHz~_UOW@AT5BiAmWVCulqc-NwL zOgCpEDr(omys1?6fl1ujq*q0pn$b*by3d7h-9UR*GSi6Dd{*s(v?g%(=6yG#-n%=W zmP`{nvIQj&%N5hOuaNxkx#sEVtm*hom@3;Wv(4lILhW0yjffVRkQ=Jk_Bom(?j)^IEl(%VGOMW31zolasJYbAHT!?)UE-NVbGu23sK?^_n1k+aRO3=`?5YC7q}{b&UG=iqmi zSpN@eZy8%hw`Bp^F~%6j%udYA%*@Qp%*+&XOffTa%*@Pm%@{MoH8YR%y7RrfR`*CF z&7UikbXBT4XYaLPt+Q*>b2>{AO2&bBt;v!%sCcf4$p!HT{`Ru{E38tsHJEW2DWIx^{;>0vWUkQ54Z3JKeDnkf z%Umt9g#(Z&;lH+^By)S>vmJuOe5wC_IoBe$XbA&J?u7163qo}oPoDRUNnQEsx7&Kn z$&Oo1DK+Haep_}y?5NEN%ixp!*~0H|I}!NtKXvdzsGb|^B8rcNNSfvHRw;#S@531f z8)_JS-%PqvBwli@qcA4H#!r>r7}I|HWv+97_DiZSq}_JUToSo zl3EHnOk#-jq~>t^-S6j-vd?fsM3&2diwr9~4- z=U^p?Mflr;;fXJizw~}jAx9nkcyPby0h=-1c5ra*#)R1SHqKZVVn9vdoBz&Z1k9#@ z(sFF-u;c2t7`u#YKT08UkcMw}hJ3jF!eE}*JM-X$9O@e!k3d2n1SfpXOcwf4 z_RruCN3J=xjEw%euae0K2Mr63A`es6?DM!ND>~LP-mJVTR#v430J8H{DAi*2nRsBPY=UVb}^$dd>0vO!2X{i_}%XT(-7k8X`y1n!hSl=_S{ zog-quX%4UfXH*5tG>O*qtt;#rTRzU45Ycg>3s2f@Z*ND7w)p$1R8Im3s%I#72-j?0X(6$Q*OXBJC`S& zuJ3kMtm&^~_TJ}3r!uB=iYen+>|#xkYMKrE=M>T3A^-RG4EbP6e=f;iq98&{QUy^Q zaa2qV!K{*8S}x*}ZOu>~Z+4p7Sxq71wc(abwaImSSsLPQ`6SDL-2X&lur&J_cs3J8 zUmAcnx;8ff&P)q$@;r1spY%{8k3XL-{U()6fw)zaVS7IDwq|ro&u;j~ARGoR7X9A* z{Q18Aa9Ws;y&G#&)^zrArT10F$k=76;g%NITbFML1H*Fl9?p@ z$bN&kUa!*?{Zyg();!vQM;PTJN?95Ish*gC(~<1YZFiD!Fh0=!xq4qyw|VXt!Hu9l zf%|uIg%k(!Payw&T|x{h_XUqcQ5-88Pq=X)6B9uDC!oBqQB4RqpKwcj+etFAeXt?@ za5NY%OYfH=#+xR_q}`jG4EN@AM*sw$HjLs!q)7ZkoDYJQ&TF!A5@MB+T7SCcN9rQ6 zmp>c)X(Ap6#*cz6$wsK?uvXp639Fr~(1;wo3 znfkMTeXBi62M3Ec8I$tXeyhvI2m9hn?Va0{*ZnUP73(tmR`iFViD+Nfo5ChR@s_ho z$&`++tP@8pJ<(Ki_}u7fpLdOk?him6WJ-eeMfPbE1QlmZ_=&0)o7W4Q=G}xLUu}=; z^UvI-_x^c=@w3M*TgX@0YFab=V;3(0?M9~~F7Ae%eez0t%?kH_40wgo)67Vj0nQy66XC7(Wj%nK{xnDeLQ=`LR)QK)e_2RLj{LU7|NY6`AG}nsGOP8&N{< z69))|`}*rQ;&5HTU$0=JkP{ovb8NsX^ugVga;AnVectbk{l~L8PWK8t4|b%iC$RE) z`+Shk4S_4=%k+k}W!C04Nl^^9FaVf%M#|za$mMqCAL3ZB{#PADdLycEz?xLh^^moj zH|-L3^N;J-RaMqKq+=J#X&-HXdttj-0}; zMI>vbSu`g)uulg+igR?|ji=V!2I-7FchEq2-WWGGLeNcq6|4dg=`$f|yQY<~ut^2z zim;aM&nDJzDz@o(QwUY+Nj2hXsa{?RWa(e)aAX`iw^T96fsH9)a;HsE)7ISQ`2Z0j z_?;(2t7FBrBI-RhoEDR_iduZEn)m)eA${pvNWK#a`O*&91qAEuB6m-AbemkWQT~YM zTTiVDRzqM5HajQELkY5M*MRQB)kMChZjGOw1 z#n!7&AG@~Bu)Ci za5DeAD;GZ1d>USeSObHp^_@JH(nO8%^2TS6)Q;4a0!}7-@s{;f%kfBk+=u=siS07q z?DGHWqK)PVo{Obx zQdG6$ua2GP`zD26Pm~*Mk4r^83`i5ME6=W*44hSWjI64iw)92gm!`vEiT80ukJY=W z=zpSFAoCIjxX#~YC35;L&%nB_lwQ9t9+QPC;y!R}j8TSKA#x;$S?0MVffDhPbo1E@ z5oDFEDBZ1csT@VSvI&D2vhmasP7!i4zv|rB%z@U6JDTOT=47p64Cfl$9!vtcCH~md zD!L6+8r42~8z*$@NCLSrRAJ37nRUyzyY3Aq&#~11s@Eg;&i45F#1TZ&cl7!|N$MT? zm5K@6l^HN6tn%OT{HUGX@U6&OnIG#V!G$SzE=Lj+^4)HwQ^wE=;2phRcb$uHYrV04+x&qsOeHBfZv$J2FkZpd?PB1g=6)bJ`D3&kU|2l1 zmlbZQ#J_J`58yvEh(c-1Wr%FRzT8(y(x+i(Jpm>ZRd`)~3OIWPaec-{{bRN@M4tN~ z_4n2K7f2j3m}5;jn^gCVv0u-k^0mWi%MN`()S-E>iSaf=#C>OsUfs|t$j84YK(V2x zh7NP%2VLl&Jo^3W^^8nQziR(pA`0cv?itz6>L{NaSGM}eFEQw4aqhIs&j%(1ERJmD z(fe^0&eU>HI`Akzc#BagPGVD8H9=LWxCFxs&(a$ye{3c{lyl@~kf|ACy^6&I&-Msp zBGqX(FxuqOe9MaEsU+U#4$MQjWoTI?4VuyKM^>;?irVIFjc+w-yvy#qA9CBwxV#8NrJus+_Ve=d@H?OP-iL>ZAlq$yID$HxZqy{> z>|G%@;OI}~mC0LDa7p`S7d4B)l*(c6$?o+vG%f6Q$Fqdt0f^j$foFK-_0DU+?wVKP z2MySe=&2&NnxhfMA2WnL42t=RU zr?PryLe9s3R#8#8nRxz&YWmR0E;|3XYmmPzKTp$~cwFU6Gh*t8WQEMMX|6Fp?U8w& zUH9daG7CUKDbKg(a8iGbP*>Ks{%p%$^F{Z#o6L@eeD_507b75MF+O^&gf45)=oD6I zEytM7pJdw&4mTS99uWhY=!3YcH8uGJwO`_1PLWk){61tO`fko~?KXpZnKycSTApE;X&~}0MSH)NV z_|HGyP3miiIEd1pr+H7jFJ?!UK#GrsVet{RGrl7rcF_J)ats^Zp`ueb;f;i@DKn%T z%!XZhhs<2`YhePQ2>!aI+vScHh|;iN`{8H`FO!nNCZMDpn6<0PO>3&2hck{bR~ z+v7r}_iHl4qi-P>mue?_z&y3#5T(v%@PAhPz2qT}6$F)guN%GkcTR7uj@B~Bu`6=- zr9}8z`vx*sQ`)#$&uB6vj$<){CI3lU-rq>}2hK;opAee#Mpn)OCJ3gFdzS3z&uzpP zAC8|QH#&tq-=X*Rq+I~S@00f@y`bA@(ETvN~kqqkU9VqbdJa&M=}(y%YP zU2hT?zo%O33+E&2Z4>3WtyT10=Q*mmZiN(I4ug=^@WxNi>2*+5!B%_6MQ|B*ANjPX+Zy@>HOydV}7677Y?q02S?FEPOh z;515ERe_lJNu+L@Y{7L0fFFpgNQ&*C%%jcuV`qordA4YbIg&I{GMEF|GFcZ_om0u> z*DFdugL6$f|4r-QYCT&T4X?(~m~rm1cb%7=;T1kGtc0(30mi7@0LAqCLaA)ffwk1h zdd;!7lDP><3D44pQ?=mx9X{dJ zjL+2|Y;Ko{^C>Ij=Cl86VwRA)mzW<=ntZidxRY7P`CLue7zTRAYIwSrpw;dP^iIbw z@38W-H?*D zouhJS_;(*@SjNKxEHZUK-k&n|-6ps6hhIU8iGMKq$o=$i$0=(ogMhT_CX-6gIGpG; z|0lX*wU*($>m+E~wUYCZ*T9L?-B+urc1N(&Z$1i*j`;j-<21ok~wH}VPBvB8EG0R*HS*(gpHkuT_`0XUH2#pBC(QoultD2=$O>13b z={}w+4^=u$RJqrSp&qfq5RQ~UGq-liF2L-ouUa5)-Z_CP+j-Wr->g2XRa5VL`3n!< zO<|`Fi0GGV@ABYqi@?`l z#5mnl3Zuze<6C9;?hHEpruc8H3N7LnK~|zLZ-5!@-9_z+zg&sm(}x5qG~AL;%-EPJ zJJM+1+*U}VoVA7;D@s;%%90M0A&l4!HEWbn!bT$!x2baTXjl@vJ!H?eF(qFR&S>iH zjf!}yIjVg44{VSaGz5DEgZvQ2H?6HHIpPSLUEqE|u1UDt9CJx9ev80935LSA-ScfT z!pDbvW}kYWu^o1Menn$y)&KH@Tz2l-kMWvoYH>;0ygixHXi>_7QDNrZpLte9rnZ z5M`o?c4m3K7Cbssk2!)X-=l_ts7Q_DKqU{ z%dP3;`{*upK>SQIXn#WPjc(rDQ%12S(Eb@KZ%h5cSjV>#s{F_;-*YX?QK{q!L#gPK zY&!tFw%JBHQ$tA3?C^X?Kr^2kn(!m^58=DxH#re+F( z3}fq=jJff{M8QS5Agd?^Q)f8(umZ*2obsPN>fLA1*+YkJt(Y$y0kGl;zRjZ1`NhMmoMdzRYqj> z!gRiesBI!oz)Sz7GX90c)F8c>9w9M$;~M<_fR^pft$;>Kxw24Fgh%Ob(LlZNd|LJDCk+Q3EAcoHVN>J` zoDH>z8$70z!l_>NmM0QvlD0uw&dyDxZwa``uyUqDgKcj*f+IVO(7e^*^~golPM$+2 zE%r3RGZ%&jGdUzd+FQ^(9v?Xw1M^p-kHqJA1P>Qpj42Xt1rXVXPakF;EC4Z{6%SAp zNvTN`&Y8XUmf%?vYl#kw4&Mwl&sIZLM+w!uZD1fAFoiOg-UrW+p06fSmh38Ac62A- z(ihM7mG><+_64E+82GUmht#_`;?c$R(S_=$g zzJeFiUdG%xtWl?~L>E2L@V1b?(N@r&^dEz{#2Hy;GQM|VU4cxG4HS}70?qc0b)PmH zvz(DhFIEc)reCAt)VWPb&5<+fS@;XOI1N+IrzpAJw0zQ$X&sDQp&yRh_`WcQa>s=* zcy!QyB-^pzNL^A)Q((%1qCr6WI+3M!=c-G;-MTHL!I|9*j{B-MDjKO3y2uuchwHl; z3sFTY6_E2j3FF3i1g(ygXE7^)(u8q)G(&4xAW+=CQtbFb(7kaN7G+`|t{O?}Vs$jO zBkO!Hg-JC>!w-%3xtFtfwOWgPxWbl{-rApa3Q|w88Aa=7UB2hrUYk|E}283ry; zRPWqzlCsS3DTvo4>rS6|BaE}I<^o{@h1IJZCjvfW#5=@g$KIXLs@2>x*PZZIS)IcH zbR&CteC@RW5KCy#HO~JZo7BMxT~a3IRN#Q8SU+-I`l?Y2NH2Vkg*VrNy?kP?nckj; zk6Cnsss&O-{@1#-C=)8y_YSU1WSLBlCiKV}fweY0bcGqUd2YQf*ToqwyfR97?Sakh z$m(}XZhQFAJ*E7v!Cov`Ve;h|byRH9+Pr$r*VyS-u>G?&?BgRg`>Jo(PlgBGo@xx{ zl-(D2?~|dw@kn+O01NQSI)0>MZwJ$A7DXD)?9v&a%8oeWj8v(wfA(x)XG9=bCo%Df zT#|E1JDS9T{rC~9m_!Le?EmU=+pG&2rEKrn?G_pd`mMfm2Y*|0i4~D0)u|Gaa17Q_+s>| z(?ilvg<({yLUX-;fI}DlFytt-)i+>PZ(sIh`p4+?9pA7tS_acmn!xN_oF`GYv()7FpWJPu9>BmE-?1uSU#9SS~UH~&oP&eC2ARd zPoV$|4xGptwp_sva*O=C)aVJ|(uUd+0ct(s1?9NUsHOG_P|E&o6k3vwZCf($nN3fQ zS_U;%Q>wBCd&+^4np*M?95w}|pyenSk#B%Adk$83I!Zo?E<}hG6lgKJ;^X2UtRE@J zAw8*JjDaXP;->|sl9^Xa?AX1YL&PYt%_oQ~+S zG6duW_Xo`~FgDmlkt>^1Lpw^UDR(2)MwWzVq0Xab7Rx}t3oxoCFpw<9lH@+p0nGQT z%=4_wRITs1n7^_xZWj33D>%+Ly)v|Li}^6Ta4{`#GR9&-pWO!%4tH zSBp{BaD}UDi#EFYC~s}{+58f>k{lv!X1jeWJ!SdZ#2$DqDAeo6u8J`Z4|vOgY3|Z6 zvP%-&Upsq!_W-F(-;cP9or-xL>l!;9^;ury2i)0oPf+cEI%TBcg@>4##ks})K7`2O zyI#b={53*ev*s;!u2-;*>-3RqZr`i=bgqw} ztPc#Fr1b~13aMB6X{ipw&8X* z9=K0kc;y;}z~%=M=-Db@rpUrF3<7C%_I5ALpAjn28TGX^`p-2C7twbGYL%fqE+%@@8ilHg_QimhU z1o8XN^On4Cz7aw7jUL15Ok*aD89-$R;)9Y0aA@&acAEloc@zj$f+>TIykaIhkR+mv z+Taf`O?)GCyJJ^y*~gF_;=|l5V6jd^##^YQLAdge@+^hTF$|G>N+j^r71;Or!2O6q zMT#T|cgE*D(4PW^P(h^^Sd?3~op(nV8$Js@cmVeCWNK@r#c~JZ#fs%~_n*S{H&Q6Y z^npcJnwBb;aTog~m=n)22~fpvPiwLUAWtsfGo^y45=-S@R+d*cR?VkZ zFoe~eSWFpAt@g~FDqgw5>+xxFOpA=Eq_4g=3mA_qL)F^f1^v>EqW;Zcg}&laD2~`L z#~6>wFFOS}Lj}y7;F?w_MZ(aWx{a-m`@1*3RV1ItO`sB0N~G!y1|*G!Ug|4HqgjzD zr!BP9z4NhYhfnKXA}$$&)yMN^*VmKplvZi{@V>u*1E0vaW*ovcZ}uFeG5JQxXKbwS zytp1z(x(W@=q3dz;=Tec)C9#y4n9LXnNK<1<-rt-N*HAnwgHkwU$J|Xof zSDPv5Wh>b*Ww((C=U~O$+f;!9yiR&c7&SLS)%F5>*_%G$puzM5?|}3NS%|zwFT7~4 zO!87rlN>ESBy?#f0g2bx+>g;!^;#ws+`1n~`w0#gL8C;8@q4ROlpt`#G7&H3-wsND z!oa61>C`EnD-rOsR;g}yIE*2Ioxca1Ba7Uuke(%>0K+gy(O4U(eWf@7BnU0-aVgn2 zePK}H04+OF5GL;LFfxAqbZm*x0U3G=(gEO#mmN4YKlVK_?};&)s#VE`PC(4&XN&-o z@L&A|Bre+uzKiFC8rU%%UO?wAO^XB>S8I=lJ+C~uV@-6B$1T-Za5;MGY%UH&T0OW^ zr@iqEu6Bmyqgwg}#B%lbtnLpcx+woHFlDpeRV=Aw>!;G0;rDSVzl^HGaP$uji0;0Q zro3PbZ?B>RU85h>5s!mOoNpFkiryQWky7BcToqia7D_i8{1?-x2d^m%dcx4zxe$#n zyLN-hMIK8Ty#w1MBelWf^W=nojNaLg&dIw!v-#v^dVS&KfvY}AHGGu|nvIq-J{<%{ zQ=N4-fMAg2OC)g$d9BONw5pS$@~^t(eBO8I29;YBNWj7Ky=qi7tidBLkuludFRFt0 zE?Ht-`^E|utit>-=^zIoKZ)hblHwAHpN%*XJ%9UEsyrX{JwhJZ^@ecBd!cL$lh$Ut zaXX+V;zH?tCKDmn<_e+MA}_o=fi>`2sB3r70!o%VHhcwP;ZvHzbW8hnTBkt+!zabL zUNWKY(6(jfRg7}YSceLSAaqwoX|8C6wl)v?grb5W^w zM2wbESJU0=Fh}9?3!db1;Ou9vAZvlo9mpDTth$aS_|1+HH5zqn!s#dxrLAfgyA}=Q zPjMNd73zpb820I@EI&S43fL9TW{|Hp7A0#tWCUfM@1{apgi*xHoa>+M;Xc>8L$$hQ zZtQ^K3s@rnITW(J_zmvL4Q$>r>nLYJzev)2^AuioDNiuxwAbC0NTS}IZgQaT!@wP@ zU*AZ`#nip-#zLVZXGtO?M2ihcTL0BR8Bf=n0G`o_3{PVTnG_2*jS0>tmkW3_ixg*d z7LcN_+v7<-J2$d&5@S7q+C0GX9hF1D%sv2V|2|GRBE#KJxe zru1)J?iwng@U0kE4`SSF;qdbXm6l>EDkY*F4HHtFClAba@A3_3qbG5Ll>&}fgkSM(iIDgY)YnR=gB zN`L4Q*B2Ea)%XWpwbI!RxsHw3|IlrCK#tiF%4C2DTd9j}N1s6hf{qsK6BYu2Vc> z179SQTXV>fH4^h?@Hx$}K8Y3gXM7;ObTCmee57u&(3GWWm2i5v5ncAs*}hB}4eVc5 ztdh`2=@mF%(n}jn+;u1*91eEqe`!yj2FECeFv{?s@W#sON#u0lF=?c9FE$Yf?|N|>}3tqFwJ5JT-7jj$=J~!!D!gU z>@rd@-z#<$3E;Y=s7%>ZtCKN8n*jmWghLSxV#PsegCBwiO4i{qwWj491I3jNcZ_l) za~uUiR!kDMU|8;=+SA(A3pz``w+b8D)WvY1*HBwopyaMZ#1+WOO-Rx1^3$ zfhEj68KfEV`Dc49YS@S2WI|@h$U>PF9fU0CEt6dC2c4f%JWt>>!Gmfil1D~G3Oe+Q z2}b3WB?5-5$dzdXTsnplXuqU>cd@ye9f;mZO6An8Bj$#TX7b*3$B6$|;lZaA4+ko@ ziRXyjgn{$hGWRxQ{BLKm_Et+6eDV6dJ_@%6L@f#>Z$)*Kr(!D)gk@)(-)vdenn4n& z&ASK)rZ$M7&TI2s^9&?Ye>o%78Ib!TR`SQqcJ`m2C7;5z(|<>V^y!Y^g4`s1(-&{0 zRcqtqU>=XDUd6!R_~yec!eAYUT^N|Ab;UcD$k^BsKj`p0Q*qtQ6zbFN!O-G~mwrtq zAd7GCu$Fa7IDwfjk5gqvGkd_B7)5-wWg)XO;EsPQ4IC_M-nYVsEX*)fuIz4-#p4@n z4#xoMN27Vh4N>V!LSYA)F4h_(w zi3!<XyMg^_$TLGt{j$fcA3k<<15-CQnEVz*NW$fsu_g?q;z)5|6Ni>_( zlW878e5bt7>a>d}ukADiG@4q`tiQyMQmnokzbE5cIZvO=^N&WIO0g95%eYUd1O0}t zI2X|!+ZyoVlNXLm7r}AgY|AeAct2!CFD%(8lpI^-(m*C5J4KNQ;6S$KF{h_1W4$K; zB_xQeQB&|<^}hrYm4$O60we?#FO#~}#y6zW2U-Gu@#i_(V>vn}EZ{0Ha}Xh_cIIFM zr9S9lU!~xHw6hKwRpx-e3rD0aV_ti;qb)wKz%=5nzSOMNMe zcc#Vt_+vao0_o(%D0`h0bhqmv8%sH-biBT&4?{kizQd4kd1lsB^*akGMsS(S8&ZV0 znWn6=x1xfA#ZF!JCcU)gkqp`z zU+z6}RrgDME?rX98~g!X_Cx)rGn?0N{)OO~swj36M70UpBoUz3EUla0KiS`^_!bM{ieyzJY@I3&lcN6|8C~ zWNM1x88{#Rk(c`fXW^I%LwPscsjVmby2x-BL%l5{(_FB4Y>$FP)OEl zk&ZDsa>j|iZ{5JF6ISg1l&?&neEh9z`Ls2qphc!u&M`Mq*eLcRc#vm*(11P#xPe_- z&8JG9Eq;C_o;WD8$?S=WNbEl3Q!H%i91jS4Vk-&GmE)sd#3^v>`?}Eo(v*W~6*j$; z!vFH$QWzl$wci`HH}oIOr%=Oa#h3HLNMYo^n9oqsOmM!x$#vQCba=m?nQiBrbZaFC z=NnH93HcWX@=lh(6fPHC`y7G&oQMN$;d&< zzv(|@JmAAI@AY^Us^EYMsnMQYp>0Q^WA}vSXWFWcb!eYvooGZJPcYg;$iE2RKE*Fk zAF@d@kCziT!Zee4XF|X&#m62>xSuT(GoF*cSiRUk)rHjm>df;sjQ%A!n;|*nboAM$ zbz?lIO7OX(gB7*>eRg%lD_(6Bj^3NIZ3DjMh$!yJhS~0qf$;#UmXhq?&unm_YFI8Nn%2} zp9ZoM0vTh?1OxVVFSp+{9AjyvcSI`-l9lDHJ2M%E$*Y`ioO$=x(r{NFUXRD)mb5!PZp7g1#fS9^ zAhk8m7|w_lq5fZ+eI@2L;v7xi+1ITlPR(0-@mn3zFwT7#_iS{A=UNBX1|RH4RC9C+ z6q2DwE+@TCrs-X5eu;iKuZ*T-ZWER7%pv842-c^brTn*<1iIDLbV3yez|!18(#O!N z1bo~3u1tRRsb>?{f4EzgQtDsr5{R>aZgp6Nqa=180%*mD%lJC9$GN;F_nEGx)f<0G zkxrNQ6SzTII?YDL{}$&%e{m4Ih2lfb4U89<@!gd_P(!piSLpTjSuYGPz67e2D?W_HS|Ex zBYKod5?;C9Pid2$%TfuI4-{07j#QsWTuzS$iF0g9^Toc$jQ2)jTeo@^UtJkc^}k*0 z_q$)Hjl8n+)k^|b9fI$m>he1l5MCpiYH167e7H+l?@YFmZ81y64WHZ@gN_>tYH-1e z^63RwYTV=z_Yl%Xot#-L@4(|Wbb_8K?%>i?!QN_EbDxv!S~^{(|Y2cPz-h$5HKQ!sk;b zW8P1cD!{N!Jeh<8h9me{>O3`cf*0Puz{(BFh>5=-)}-_YmzEBw6#0a-Ii5)ujj?6c zCD)0I3iJN7vhCTj&_zeM8cRL+`->Tj9c9CXq?h)$)STbT^?1&0=hdrxOG1MAbTdIj2)nfKi}>+p6~7Z8%#(Q5a9j)(sl`Ojn=$> z+2V0X;$6M?W_s4K?bz}P66Kqj@Z(dAKL#_UN&mCCJf%gwaQX7ARG9iKT0Z}Gg?iP1 zpX$sOmCF=HZw zXaTtYZN2Zp%Mbs7*nn7YGndJo9EAyauV3q5pwN}a11pFk2O|qax1VXX@AyJhbH`=p zx(UrRrWUG8DW zdNZLZozBM1-@xRJ9yYXvu4NYXwqDw^*EVwT=k^wEE{w4`{0R7>%7$qdKmKGgRgrs& zPexc1G!V>jiucS^fwU{3F;Ypv&TlGM(n5_{b7C6ITsLx$!)o5Ou(4dNSJ zgXyo^IMAR3TUOPXO|Or-m6|(KFmYQMv$rvPH0*z1e;Kf%jU(4qf6P4hs2EpGo|)pZ zycn)vAcvr*objVMy;8S7#Ss0VG6|sBUZX3Y3~KIJdv+cRi#@#3TAC`74G_BUskJ*X z@4@Hx+-e{UEJB)BsCu&i1WxqQ_g)D}ekrO??>HV1op||RFl_}X`jzWIP7OBIi|N%I z@hPBU1Je_1BGeJcUK?vKGgmz_f=UIuO*g}~Pa$KN6!d)L=+79Fw0PDWJEeU>KS2;$ zXv|}H`5*~QmVXIi?9Rs+Yyw&W5i&Pi6k50wtBUH>2|QQPYxk8DAQOyrQ>4tthvG<6C>cGs zYc70_L-(&+JBY*{XO*_@>}+YG{<-`-2{? z@w}5oNfO%@swe?7Dtfl_{yMc4c@#-S9ylgw?*ckk^VM84YV z--UrWLEy#4$DynI$ea*hBDN7-7op*JUgnZfv*%SiWuG*z+Lx)OeD1dz z&YD0We&xwjY~60_q9t~}p5B%yA8f$fZj3IlH`lzx`W$x6Inljj^ISEMc27FaKq-AC zzI}LS4F5fum*{+j8_ok7Ai;ZZ@?c=ceeVr!SakAL!avS5j@)M|qk?;+W@Zk%zz(*9 z6DZRU2DrX|BtU{Ov%*bz-p8S^Jr=yPl|?S?Lvp+L>TiBgle;+`#THm$(v{pxK4@Ir zUp$KEM3KngSiS>F+XDJysDOU_fccDO07#L?05GGf8Zsr?Idb=^epp&;L+v!0&8#z7Fq%BlSEI7;DL>a*u{5q8{|OZurLfw1rQc&CGSMy|Qgk>< z&hpm2??j) z7#ClOBMJE6j>l5(i+!+h8_yLeotu5FVrv1@A?or`cRqD=|pE-xx`;65d^hQx@f0H$=$id<%}KxrqF40ki8KJ?r^K8($sLu)V}cN zKm&!c1a@=NJ_=fUV%2^kR0d4uUY|N)za^($38>))jn-2IVNL)xjcx*8C3P2Rt(Mv6 z>hv(0qOftjMDx)w;A<%-U^iP za2{y8PV{GFK_IN`3=tl$3}iXN2_>KlV2ATF%+Ueb)s|EtJBJYUs?drlzD%V517efQ zt&W8NLkji`=XuJuna|q3tU&PQaGTWpljLT1#X38hs{dmaiialc`JW`C5BtUi00I$z zpjdYQ%5^MyQ!v1>VES4}KKZQ!EZojPOwptwTCBN$;R-VNNHqD;*bt^nN3crw6ADFO zq>P{&wkpfm#Ar0a>XOnBf~Fw|=v|GkiBip(xXTIKfZ;}&tB-{?-uU1R_0j=S%qh!` z=>6%+SckW7mUrrdeL2Y@G|}4TSR$wS`c+GMIM&JjmfR@9$ziM9wIWAj?cQ{LMH5X+ z2ojq+TZ+Ytr9no}_7obKUjj*Rcz5)WVkMc%d~;Q8#J-UnSE@yW+93g#_?NvgQJW2x@%s7ZO+XttLOp3ruAT(Qx^bYHrSGVop3Rdwp{C? zONt`a>Gdql^pCu`13+A$b_L9LrUgu{zWX zghY`;s3F_^NAgr_wvGp>-tHaeQxD{GzlH$_K!1)K3lEcc-~TLNe;tkHstx>RL5mdv ziE6JRu*7chd5%>|e@a)Gz3!L>g0~#XF+HW7^!AVkh4^ZhlY#t7;^k&C%~A*JNQojc z%8!ah@}EO4{||d_85~!$t!Y}8C0oo)7Be%GEoNp}%*<>HEw-3SSYl>ow3wN(ge7Jg zeW%0UJ*V%??U=aT(>*i&TT!tiGPQGOKKZ;M`j^qYF$S+x+L`LJq#64_u4a^S*+Q5MppF$n0+)m9JhMj zA02LL1+EAosWQawsG_0`EG+q1Sh+szfOwKSK{e$v_!-5yNP7F7VpQx5JQ z4=ajc_0~`SSd4#?=(f@l7tk#yUlEMaTFrQUG%6p*8C;3>GaGs5RWA1em{n($3$>uF z1&X$Ph`L%DS;cSWRkr~|Hq0@v7!YKUyTuH#;WCHXB{5Q}_kv^u@srB?N472>OxX6I zsDF+BUR}jo@Z!RUYILxHJ!M}NK1Fn4TCR_CFA?LCFX~>j69gF>o07`Oda)Q-Mm2?s z=%}pFR!mz(gpu?Y4*VMUK{2|`-8>#BW z`HXG}OXy`Q-%*M53}&qfP6X|~^s#=Oyd&HiqZPmsZzGG169SHkz>4%aWYbHvs7m8# zZIOjj!f*CoQ?bom+dr7xO)sX0`J*5#skd=*B`~wae_zQ=WmKRu()Be`LAvqKbEk&*>u8tfQ!eszs< z?Q0*z)$&#h(hQORl}jREX;_#a5t}R#o6|Qm^d5malsh&629eFs&`4H~-aNH7PZ9;s zc{qB?-QzI(5MiHPRD(z%-~iF*jvme@wP>KKm%^ON+~h}MqqU)(|YD)SVAWWNukin!7P(n>ZoKjUxQ*v*=HsS&ITjoDj<`e6tHdK;o5H zMY86dEG|?3tJ+u>o0ikX-sIVtZ|TSj`k(dC-D>`w zPq)NEKDqULZB84|V`(n8B&jju+rUSn9g_WidfNiO`=Co~1@NQeWjlc?bY0%i;<{#s zGp~AaL%w)`VW8gipuNoyAb+osY2i}1PUp^Z#9%j()m^u3tWH@S#xs{sUEaWwgCSs( zeF+$-yRjupPsDbQ96m!9-+v)0P+Gn_Rs<(cgc;xRo?l%i>(GSLb2f9NsM{x*r_6TA zZEAm5sY8?5@a7bx<7)C#??*A0*_X6fULO%z@9GlxXxq)BkK{)xl&^6d*iwoQJ_J<_ zr>GWzcY-?m8f8!?R(@gwOK;TJ6))eqSw6PmW6x2vnSOFkySysY1%<$xLbH~~TUYtI ztN3Jz9MsXGwQS-l-kWVFU!)MU)QMI(21AkV%#_ul-VaVksf-PFZE_cJNztMh4s%)w z`Nmxzo_sO{He^EEyYGjinHUYlGpt*S+m-xws|$2Ig0$6bO*en2{Tb`tmZOsl2-veT z{G+6Y30twz+K>sVE?$l1LOi$-dQ;){JnI#&^q;*e3$1qIGejNsPvt1F-e=908^ifG z$A^yJ&%P1xMn~?osPWt|wq2`HK+h1&%eGdKZ7oy@5-?V5i*$q&wInbi#M-~n=V<_V^7a%CR3F_)AYFF|gnndWN`JH2AU}yNK^x>e<+&B(2(#RC*9FuM+95beUfWRQgi$_cTj4&Dt&`bbZJX0?z7taJb4w|fiM-C-pP z-6D3Uv|PY#mVfq_YRPS0s{Y3^u7sQ3#g@(l*3+nl6VMBMWFJczTs+%stMcFLY| z$zNKykoX|8gjQ{@?6N_7w`NVR#!Ds)R$&RX{VK17_p)sJW$QraAag?T2PevXgCUO? zO&nFw25T3E9WZfb^k{Uct?Qo`vGrf?`XoA+RPpcfd1R;R`S!*a5n>@0#ODq~P^3e901dd-mFxvpQoET3~F{5^1p08w$4ta)tHsF8561DnD8t6_t@+ME>|YO5z% z!05om=&z!YduS2{u#p_Edi|=jWLff@v!Tpu>oFKS)HM;G+SAa?T(K=jA?IfJm}v`; zM`$Q_#tF0PSvW#VcWUT>EZ!<*9#|=-iz48e>Tvg!K_!7{b&pL*2UXJ8JdclT$N8AV zHno^jiOLSJG_K#4V%vSb*|Xrd#vbx#jjpyow!FzxV`<>y<2v9=fFQN9HyqJ_vYCZ^ zH|+^8sCSwoD|Mw7oPa$T6ZrW(q>K6Xt>eC@6wkQZksjD*I=a$}_*LTl>F&0|S3q2= z=Bx?T!zuKn*$G8|GTvLO!m+om^(o+L$@0tJ#z7$jtTVKar(SCO&z6J^ud77 zimEAeH|k(1XS`+j6L6LFr4OFp9?GBhZLKwl9<@mFww!p^)dL|*`ngp4b_z0h#w~7U z{9xVBnTb}JJdcN9m(teE3ROU@z}doLL1*=L_*=^uzc>-*w@09 z_|sQ}bgSLC^S^;PALU2XES@3xr+^xVH)?gc>Aix0$Y|Ty@xXnC3rFL2D0$==G`Z`n zt@p)FetJ{)z7epfo$-0nVEW9;6rcNd*DqQCJlD{kPmQ^{;w@6VBuF1Ev*Fi&Ov>Eh z)7ZXUv>g@A>k^HLpBO64Hr#~$m3aHdh#05g537>tYD=x(3U*h`hsp(aZr$E>DEC@NuJ3_Q7B|-`9WF%_=;qU%MnRO2ZhCgf zE-x39X#~o~aV}2j(=-j%inzELV+zhtAK3aP(ZE}>7oo?WOmoZ03N&(qcE<0Kr$uxm z?M*&0sg8!OVL{m663D~=MLCdtgE~2$`YIs{uR6dT=aXlol?~_Q({_K9j7B~UYN`gx zPw!K$*CRNJHT^!uLUA!sPP3ncQJs`cuGQqQ*o54TKP9k?2wdxZgmIT7P=kvOgKPjYp?Hk zLIl_{+5=jcjs6lRZd~7RAmWe_K>V^~5_?)z<0h|zq&00Z3$K+l^0_L-9{<+T#h&gO zMOK?(fbkxR_wO=*Ys~)%JoeVVLP0vaoHYfc7HUK^Z*>B2Gkwz|DNqXkAt(WKX`7BD~-w3VDk zLKT|xiV4HY{D`dKPPWA@bUkIFpG(B9OmixNl?Z~FEniTtghw6tk&(WSHNTINle;3= zmw;hKAjV;%ZW(&_%Rb};QcMXvjsfpz(H}#|>)~onhKl8y$t9$|K`hDbVeof!e=V!Q zX;8|D3lt?bZ9JrI&BqsF70pTo9Fc;j?0EVxmT*px&p+mZ05}K)P zo?1+L_S8teyG-;x<@`}7cb)9{nRz;&idlH&0`@(dhDxNUB3q#6;|5+z`P7Ve*yeVO z^_de;K_G}KGtN4lEvT<0U@DdsSNh|U?=r!FX9Bh2NaEAIjN;bmHg_HG7~GRmtT-co z`HZJ^8nf@C25wS4c?EHdM8_pQ;G`ePsx{PaimqmgEt4(7SAQ<+=e_9r@ztKJkd4x- zfVB)p==p$kaVFQd_ABUI9vmrKSgQw1KssLCHbvNmjg}s;3g3oIbOjP>_V@m|m_fg> z?2CE<=hqvyDk=OQSd6I2n2fZz3@1ND_bs6#xB-qjZ|`LDv2cMQHS4?-;aLveyHFk6 z=?J|`u;EBKOYyc**0+H2E4&*hqFK67SzFR`gIg}aQ#`SeTN0dq=3zQscT&tUYRY1x z?HPgdITQhENIiz3XtqJ1Ej`-s6GeU@=lHkU2}o$Jte#*D79LrBxlKiDzOc2k2Dq61 z-tP?D86gKW>|*y$+p$>Z-)|R(&$==j>+M7aiORQ2@+U3(i7g*$;avo%MSfQRHLG{= zB|8x+G*!&&QkRG@#oao?jh*AcAb+O-ZR;mXE{^rloXK^Xp>mc3MCShoxY%=p2;ToU zu^0vseZ9Vn+3wutjFiC8xM;}6isw7D{tAQfgPE799pI14By{=8ow(UYE_~<2HZyhR zeDR=K?d;iJ1z8;SM=6W?|C*A?t4?D8VO~Vn_MbrpdDoJnq01ss5s4@?4mi9W@H!?q5a8m z+sp??7S4RP4c39lr`GYzK=__GU6Uzg_sS!;s6N%K7s{Zuxqti4pNqAnvkF0wKcLgL z3ywc1`V>`-U8i(dz}9A+c9H<_r{YtNNR@2QuUmg)KcM9ME+)S(nMXdx`Va(b0Gvi% z>rX(qyu1L4x^ZAs_sn4nb+#R6;v^h<#p?1#onvzyrDtj-iC;SSNOO38$!$TnM``Ef ztg%~PH_Lp(DkU%+??c_VYIfz8Zd(~ZIbx4ZTr<_8UJnfD&+%g?rA=%_wB_MogAa0q za`{@XsTyXR?zK>`-||8?4bMm~W@y6_To{h&wz+Z8qw`bg)p$P1EB)l&8q;WyqIKN2b2nlx1LvK}8Z8jSil-b=ofNTjHyNJbO-Rz76#1aJIS@g{z< zI5b*P)l#jf> zB$d9iAE{hctm{etXNU|V08;2b%gAURR22W4jI6pu#uKTnX)iBZE^li8)9+8B;iP37iPCj+P ze|(|!tK%yIJP+ENPH5_7tyn5z>vY=ZhHNH(BzlU1T(bN8KGFQALPF>7r^e3t)pp6n|y{vd7RaN-OBkEx;&*(iRb!IIpY8sY!Y zmX(fs>5u-~YzGWRIOfNXdcV@h5pi74e*derw1ISz#sV-Ds_v?~529{ybI-grsyh-{K$0X{AD zGkR`6+T0xP>Ya?>CnsS|F+Gf-|1KTcrJeo`icsHR6)D3Se=SJLY|3Wd{PSXFnLfg| z(OFO|La5>ga^VYEeK1WOwN?`Zxj<`o@gmQX-`dYGv#^|V{@!%IizcpjWHEpbxHgzd z$TU%KHi}DST0;}4l$v}7pD4@4v#ZKOrWt!O$MjUtBg`k-58JwmBC@l;P>qa36b(rX1QVIcH=Ay>>FHB-^x3K@17pDzS@hsaZ7R7E#=Ih}2) zS#ANbncs_Thb#YGxa8h8!Co(!G{S+AZbNb$s%w)PM9SHm<9^~y7DK}G3;{2J|%zUPf! z6CT6r$m}8sS6s@J6}V10C9#Ct5-M&w>9s>_NYrP)E*Q9=p6>b(`;YObcMv-W&{j;cU(_OyFDpnDWq2&dl`Gk zTW(TnW9P?3C%r0`54KX?V`Co(>dHVW-tC?@LZoc~bR8YKl&3dKO}v#Q@q|^balnDE zm?R`Wevf5md7m{HqQR#*J@q#evp|X@c7yUPPZpXTw!JDAOi>PcWOC73tv$`1Ov>}E zG3-5FA8*1RK`si7X5N6+6Xp>xUk&tc#zOaWhSL|M(k$S)&%`guM$cQHNAY@Oh!JyP zR>3gCcno{(35uH4dMo{H=3M%WLtxclFqHpD=HbQE`r>{QM1AIJ zPG4F+G?a{H5^zX>i`rr&C;+;(=gNi|J=!6mAbUz#OqY^jYAC;Ve4INX6ZE*}Qb92* zQ?-!7l<8at9YBu7@6!T0o<3cYxb6%dlvpx&4JD{Iy6l=_5}N;gu4-*r1LI`9LmIF0 zEkZgmo$+QtfhTwWD2?S}v{~6l_q!oJ(yIb3CK>N-xPLxuV@0jAi^L-7sUvtV&SdE7 zA|ex(8iA@Nz2~I{Uh*2&hI+p@Z#ReDCVau?y(!qE4;UkovgR)h3RngfVrR@ez}0BFE?bu$EbW}@svFWQubg|6#~IH z->*n4L(Gj2~G5@PwETRt4TX#cCMvoxi!lQ6o^P>gY8sduDGHhs0|A{&NRE& zZ<_;?6q#F$|8)VGu1N-TT5F`15@!Xc)h+Ze{NKKnzn|!PbW#W_b%%|#LpI4}%<-VX z)dM%XPmm8+raJO?j(A3&+8m&xw~v&Y79%3}W@M*XG-`|U?fhlS=HOqB=PvWWQ zzoC8dbyJ_rY>h_5+)Mvm_&PRXZh_RotYQ3HFUN5Y{0ubD4Sb$hh_-$vCu2S5Xdq0> z3s#Fyb+sNaW@DBV$66rKE?CB7j1$?xfyim8srp1u%CfIEAI<0iWa8$gju@OjgWo{w8*RPkk4`_KNP{1N074CosifbS}Alme(Up5=qly4d= z=$1cU5O}%Wq2`e}xlJkrr$(9BcbsZ6uL&KGPFo)`$3vNAl)j{Rz|STq)-bZq97~rO z+j_X$PkGQlip_2GCU@K|7k_-0e~sTX%|vR zI@R?KjkY62hbxPtpC+RgJh!kRN1|k03+ie=hiHoz-Lm(3f2PMDpz)LQ)Fk|ijcjD_+vTLV@TOxvyAr;9YIr00@WzEGWq~^Kw=%;9g-j0;0t>>i6 z%Lr7!@qExZ-utzo#o1RFE$zeSO6c3U7w`2fqBPsKMoQ;|kV>#U>x=VK{5>dd;Ll@s zBH+&3u^`MoLr8do`Khm+P=5iyCNe(iN`kaSj8kobq#(7D=`;h)3CtsZ4h_xZ9Szn% zs&l?#nS#;eXe-OUCcgH5-%dSnDpx#2?+jP(J3>L?C{AVTu;(l^}+Osk`n zef?7$i$6TDw?iyy^?gOfL{grB4@6KQ`}1AytAQS<>90!RIV+&M-(arC+w7~zPnvEl zl-R&e?KhO++KdLHp}!;iz$`^Qzn#J@OcGLaNV#ag;$^`Ik!JcNJc@cK>3r z{q##F`xklnluq)y=|@>Ynrr;NhGzmtTgBOteW@w;6%9|evDYaVq?Z~pfeP`o%;Es? ziTWH1xrQA<8qVEEKT(j@z46oE!sh>lN_JM^i`d%lKa}n{)vRaW%)Oe3HMu7r3~4guVc=b@G42=hA5*e_?~}1a{m~s; zA06q`W1MZMeb!$;4JZ+v_x(n*kpDiv^XgATTJB`-g9n>iH`e*Om$5NpcT(xyv&b7a z=fsV1bjfD%3+%#Rj2O9g4P%$;t>T*6H9pVBjo}-W9%4FCWQu8)f@8@%w9MOs?Wso) z9zeVbE=^_iy#7|avOW?KwTd(0054d^^*a*Ts6I*20Dvk*U_61qCsj=RUnDZJRppI3^y7|H*3C=%ku$zYrQa6x1*gsDlTIDqliAX` zVm=}9pwIbJ5Jmbe^}J-!y7#YjvTosfjg=Y$lwC@z9ifK1xklK=n!=_ROo%%kbT(vm z$Zx#Ljh)rKMp!@PSfq?6d%vLanyUD1!k=R$O@33XBOv9l-HrY}41jqIKMC2JC}}^b z!8+aXIzC=Sn-7?C)?yEsBWIPcrobO)(;~o^_W3fMID9UxhQa;^18?awg1`%MVIW}% z>`j~(wDP{{dj&u$zVT2-VFc0oRWKQ0vfNv1`|R289>bD!1SJNN;e&5`WpeJ+jSud_ z1uE^(^g+#I#u?h=<)e-UcNX^8T&bIBW~jF@XvzwfU~l3 zom|9)+?>skE5MhTxc2a~YjFP2Y9OyQ5mT(AU-`FR(yUQe3xhSHq%n<^kG&Ah?~x>j z2H{HnVDfY5wsdJV+#YT>wp0q`cEjyWZXGXxFwPtCzQP;(oWal)a~NC>F>amyckGa)7wV@ zU#POGT#PR=oeEpakXAeRWlK@TH~PXq2#fBm*)dN43v~>p~chIU>Kx zLYEN+_n}g*z>fE|sm(p8JogF_nsgQGLQN)-%nX3)^QjKo2A9 zY*1PgZr@Pk5G{sAu2HDpy49|ADm;Hu?y#2mF>Ced2F_n3sB+Tclil`E@V&?VWHxUa z?4p4c{O1k5oAC~(v^f&q7U!1b7X*)Z_0o_=`zBvY%wPoLJ)(-s>}Piy2^1Qd0NgJD8PflPCIdhE(m67On3vNaJJK zlM4W)PRyB$`RmO9!BTB+L|Prq5EsS0m$9LyC^%*f-@ffR~9J?NOvstKYkV5PHZPo{yCMK8llu&5%7 ze!Hk_iZguPGLwOpj|kSaVaYmNb0reli$X#JxuW z>!9dR(JEKLOcRC;Born5n93Fn+802>tts|Ao75BnT_ZwH6-)VZd$_@2a6>3=hi{?5O8UeFYrzYYiL=l|>$2G* z3#4+frqge6N4?GQ@5jyoVvNvT{QjrYXaf%fEMI$fGZEh+S1Vk?SnhK9q)@e>b_Z@} zYRNb`9xCvYl>bgz`--Zia;+nzl(&13YK=?nYby%IIQrLZub;dXFFN=Mu@Z9cBRSxx zKVb|6)l;3Q(VLiu#?fUk1)|LZCp6}J4w5$I%@}E5#n{aCuh%wI`X>}f;#(KcSw!RT zzy1`=s_LB^gD0np_~|S=gIOkg5(aIU6H7I{$4Wy7=-KTsF?aqK;fyBjuPK=M>yCh& zIfm?OctQdct`e#f*+(>d^WNV6)K;wtHVf%E5{~^uqP+8q8H)dgTSoCe(k)AezQlb_ zu33Z`UKg7VTW&mQUUx+G+Y4>?_<=bLV`VCw<-r52zV)@Ck*LBD%J-0_KEW3rWi98W8IG4`7by7NWoSS z7oPm<%*@n{hPi8{d2jecyCUvs=O127omw8XCKH5TW&skHa!!T)%LVC3_(BY2T1D}a z$Y{#huuy3O;_lIA3Yj2;Zn`Mmz5jy~C4~>%^}-j5 zY`!S6PR^gn#_!mDij^+-qfT!&kA7q-&mST`lIZ>7pWW#y_tqTBmDZveRQ$01iI{;p z{?}QxbGcuf37Vauj6Wpr)&a+{&y#833n}P8dLTQME5vi_z(#5uCe9oS^uz2Odf{^9 z3;or~(+k~grcBF-iELHuT=L;MX-6n@+qGAGIr8YXgdg|=zYI4c3%ya+#l|Mv)bYSI zNQiDYp^v4`)5w~s;Z#hJb68n)O^m)MZ9c8eE5PKRE(kh^A;Mz5*OhRc$-1QG+Ju9; zcfeOIoPiKNo~-2s2u+d9foog=1LrQ(U*oY``JN@{+=55FjD&uW(z>B7mC~s*>}*{1 zBq=%Q3^r)4n^9qwLmsq#;})ftm57R_pxI{`c+OaHA`Afq5^{w^84Fb~kKm_Zt!|rl zm%sMeW|o%Do0GX;OF*YZ@1_wer(7a@(ODS)xRzVDB*khmmmTybzq}P;UQGzdre+VZ zb1~8zNS6VCdv63+xiWEWbq`q3=Yy-}DS1G)ejlqD1!(@7z}W=JJ#bDoJUhYghVOcf zVe5~Dw1UMMBPzHtzM<}_lEoyg!Ig`%joeEW=!nv;P-Z`qR)#za{$Qet+Yt(KPud=- zh#d(L2+!U5lj30zamSUdpG;vg{58MeET<+_Vs_WwErKmG|j?+S`n_aXqrhlK$bT7Lp%m=!6Xg1!kZANGCJ1nEbf~n86U~lx_zE>Vx zrtTT$)H}6_({8JG`%U^nGO42*5`iBHV6BAXqWcBkYEevJ@EO@{;5bC_o2jvk74fKP zHu;+v;G5!tbowlgtAFYHFxXREpg!`evox3R@8NuytQ|3v5%3EoU@h*j555Z@-ltx% zMxJ&(-4xnq9}7(1yKQ4VPy;ok3=Q5cEVfXVe=IwwwS+E{HvP3A!xiOK$HSHQ@H3x2 zX*;Qu#`53(#r4KktJ2ZO1AZ}evp!MkgqvJubFp*(j^|gz5o|v|kmO@ZA7l3uDS^05 zjMLyz>xspT){+H1CvtL-(q!9q8&ZA(O_^YOBwhQhVT z<7d&H{mKQjR{o8*?IxC+jPsZQPU1idmR(v7!i=7}0i5{By#lF@P5AwLW{hDC1Nio# z$*BV$! zvXrahQ>@65+$Ryfe_@EU5UcQTV>VUCVLw;YM#`!x9L$>SsnpmC)ZT1roFCGHkDHB$ zkg?)s-F`h@^>9Z}C+a*uT_KnF`CIH*yHBgCU26tYRhqt{%+*qsol5m<_~)+}d6r1H zs&y*b(kI#{xR0?CBtMVIVlXtpt$t)AY{oejah`sepr-LQ3eXtfKArWF&-WIbd)(5^yfhNzym+Q-D3@V~VR~ z7)hWzgN`SW=t3;Jhd1P2b4{PX3!Pp=N|Y3nmcq0X)|#INO! z%&)|_uRgX)ewEKNux;c(`gZwfRP}5~NdH<(N^c_b<%utI5$E+Sttwt;ei=Yokud4B ze>hE9-k)LGH}YJoEASmL!F9Wcn(6N);Pb#5)E^h1gg%pDKB+r0Prquq6{-AL%0zKc zWG1yWm^==@sm_t6+y;89{*a+=HIW(UC+VErh=mHl@fOni?mrh_Y%VPV>v6Q9H8<`eBGsn*(NOB5p7 zws2IJ7z$Y|$bZ6vbqGvphmTxt7h3@n03tk^HUsk;-BFnhnZAz|)2Zq+${IkyLql5X z;Gd7T$tb&DQDHcHIx}*==NWSzH*)~orxAvQ+smRf9z5-vmP_CvydS@Q*Z`J)g zdMJ}r2!j0vy`+O@yk9<8$uHnh*-!a+nc3NxS}w}ACkYQYm4BCU-KTN-iFM5?=(+h6 zrUeIM z<5v4IBE`nerph6r-FI2UF>y1y=sMJazRD1ETP<9xG=DA)az_?6l)Q3+InSRmilMwL zNs={|Tjzc6DOAJrHIIbUxEMF34AppDvQ{Zqt1h*A!w7CO!=zO@WerP>B-G+Un|uPa z+sEq_!SRz8VbO_32bHG+k>}S@EM<#?;MA*luTbo@c~mo9SzNZN4RA`EwT34kEyi=m z8Gp3*Yf0r#+X2ur7`Uh8LsD0c{jE?2L%gwSjn@ca9iU`nB-x1w?2;&hvC??%BIR2< z{O!pKX(_{2rAa2_0##Nt;rZ#bq2crI?cd7MROUCWzUDK?X6*jynKF56`3H25K*SJN zD5X|WWsQxYC;oH!sO;iJ#`Wwx_$&<<)0gW-wwj4-v5c)WhT*2CGwvXwJNr@XY==>) zeVDP$e=^`oDAy^3y1v{+uUERv;6mTtN7bdg7#1FUae}#K1_w#SH);aVt-3^Z8epYWSp zxUG9)nbdYRDNfZWEgEqj>kC?|TSDGFcLt0^l-@paa~ z#wJum%P?w&sar%Qd2vbM%SS1OS@9b2^Il47^oIH`;@#5ZakGU~;1Xy$+=ktlMjA_@ zFqe=LCXjeowgxN2@&eD+f&;;XWF=kWexcM+l~(GXT3mxJLm-(2ZwcCK;6>od8j|(O@pgog-lH%-YV8leAD3A=|Mr0G4n^5z3Wa8R`nTO zkN-u3+ZVk~d5+H&E*Zjp74eyA!D@6D9XKjm?_}YJ$jPt zcrFGHiC(#P?kx3-X2&fhmSNfXT!QeOuM{fgI?;yF+m@vgdGlAj>#$@?@m|-Hgun6b z?uGK2XQ|F&nN_xPLM7|7^rA6)PZy%s@A>iNEM=Gbp+e!Jy)B&!aIwTX+5K#xo)UH_ z8NngATctJSUxKzIKiujp1luDmt+ycVCL*v`tRMk=R<_>GNI# z5f`DkKe}LR1+GU$Bx%b7{%01MH-#DPE+;PInHKWG#87D2W3>|`#WKbpGJSag&G11` z$V@YR3o2gbadFTxT9^)}A+V{r&zc{zn{;@dx;y|M!CUs+;D~czzulY#>HvADx9&s z7p=!h-nMT59jpJOaYP$_L98H4AdF%`Fuqac9Rl+VDhQp(wNya*RMRM#g(DW@(U5A@ ziiCgYV`bm2iWZ+!iGWt#+UA|DpaAw_48`1A0Q4GgT%?2@VyRjPptdN=??>LllM|8p zuot%Zb>2E9{~#9gxWO!TP3x0-eDDA7~+=een9OJNec@P?;8GMx)Skx zBSFTe#Jr+aFRoX5jFE9|h9{3JO4zS&g*qfrh~`ca;!ytXL-*k|_yZM%|9r)6=fJgj zdKG;P-1GzM@tC<7JkH3@k9u^LK9o%_=<#j5sjxx^_slj)$63~=T24e2u4+?Glv9<> zp&&kd-#Zc9G1_ZPypV{lDIc=7BzLC%p@^AY4MPz|r>DJbZV(LM+525N$~F$OIf;H0 zqyLK{om<6gmu&~&jnk1>ueytA%4}^&sTZGlWFk(czRYS;G-A5y{q6Q`_=a!ewZm`QSg*--34EoJR-Mjn;|H{h>-+sW8Fa@vt!&%)aeb6} ze9*w>&RW^N9bfm^PuNU+x}w9(7WBE@QXqmJV%!eKr)<)i>j|-g*X`T6hXwPW$9imw z#FX7C?EXoH!^?is@RvfZov4pN|~e zaRblv=c!xzq~rOWc*RI2dFu*7_>t^7|+e!G8pZ+tmx+jn;_jnD|$v3BvLyeU{R z%z?U(>AUIbXV0PgrElJw)ySRG@PTo9MvmP1E2S0H-x6O6U-G|tZ+^Fj^8f0+b)@{O z_g3-dz3oBgF|mL2?Jnp^zj*WBj`wLNEHB8QYiVw}-@G?FN$(e2UFO3GT=98asEcNb z*8*5Yo4bK4TMdM8BJw98N0rEEGGgPxt<%OdwUK19b0si z&Df<;DlaqMx3b&PIhTFmefiRlwvk}?x|>#bguk=^^%${)b3fjV26$+~Q+s{OhL&E6 z$n`z)OX3=Pro-tA4XgWfrYXg1F*x0Umo(+RX1rxXxvwmL^(dP52YYXA$C<#7>!kivgUxkwCnmHuiGn^C*2R2hi30_(I%_g%4If%Yx=xZPV-lv z9wk1Sqf%%?f_wJ4+fIhVU;#Bb0%ckEsX46)!H}bOHXA~wC!fZz(A^38LMpapc1Qp< zt#Z!s_L}1dotmxpBaEL-Pe(Q-;wky14uz!VbyMcKOV?9^a3&}RWeM9Kao}`zS?9|k{fXq?wi6KVw zg;FO(b(y)bR^ay)KeOf=lOu}t{>IUU=N&Ew5q_hr$t`K{wZ#HI3WA+Iv69T)B?SJE zYVuYZbF_G{&cil>A3=_klIf;^QPO=n$VM19E|gmRzTHgT6~i5ss;?P_RNd!$&zs#Q zHR#-X5v9U{WN^B&`-bFV`^FqAMg&Er;p_UF-eEk98orFAez02{8CRZj;-!knDiqWw z4jx)fc@C#lm606R5p0^tkG|cT2#pq~kY4Cs8(DQp0{Cd}3VV|jPkujNwEAt{n6ps4;S&xc19ueDFoy3Cf* z$z4;*;&;z$CW!j?F*rnX(nQ3Tx#v@?fQPz|bK?|hbW4}2z0?ABCL@Lge);`Ds2eBY zuk3=h!DLy*FkkNOHvLAE@aB6Ye#d`dYG==o;S9 zNU%Nt?t}wGo$smaE4Dvpb;kv}Z+hgN4uA;+1h08RPCcD&UdV4UU!x?Siw!gGbw+6? zUB_^J+kH}4Z^zDtZ?b28TQo0k{Pq)P57IYdvDo8~J6`Rd64tj@u#j4ZP@RBmjy*{} z@k%(6);8_cs&eWdePq!FJ%x0`W>FwJo|7bv>qvM#qx_U@$l&@~YINA!v!XtToepww z{(u1+pS=!odNt`We`l+*SbMjlhEsMv7+F7oEGldA{XK$i3Tqj5+Oq3bj|1&u`!-n; z!wT8q9p2eyb9AN7W_Rh^VOuWIf-jN7lji1h98a=Ev;GV=y85-7RpqUTPY!N` z-vhZAGi#2#?2d4Lda9xSS=&xz^t|NFSb8UCN1jrdmsK_Haq{&h+m$F=@1jCVzg-f^ z(?C$^f+yy>wBE66+CUU<{fsYA#}ocq1$Qsl>heo{hhQQCgl1lFUA$!UK==~dCG~$n zU;9f)S)$}AYYczZb|GKc@3H?KP}fQ(tPL!8Kkj@?f=#N>PT2~I;Vg8~v!&f36 zB)9%8B&0nA7lSX$FA=y`P#KT@)8b<$Zh96ok88*GjNnEXBL9qj@QR-+CxEiSCNBB z8nfl}tB-ahWYj-19~%m!(>a`rrZZqNh%L?s%UDvk;&^Sc$%D0qve5IIj=bWftG7;E z-a?*-eR>sjGWZJ52Nv@@ya24RzC|yd%&`ucE!OjSXS%X06Z4fD_AS@b4danv1WLBP zzPO(#0T9k=CPfdP7O=G6n6MSLw|@G8O;Wpo;ze20K(9fR15XRD7asTnLTjZpMV!9qQkQb%B3%de0YL5QqKrr`DfWGyMc+AJTC5L1by2GDLe$1IV__#(h>Ix zjGLo&%41Wic&Z;|dc@V?ylI$Nn|K8;*3_Hd)2Wj;c$+%j=@q~JqXZgh=Wqcw0;Bv! znW>ufO~eqJ;Suo*ub<(1`;MTG;Nzv1cruJc`)Ep818Y0Tr|I)`3uA9lHe~bk4~1sP zww6VE3rqc#q}8qu06u`!>LxUy-0 zVyI~x#P?V%)MWYEH9B)GC)unBe#3&ubtFeD3lM7`b9r6$!ZprkBl{hVJ^(02g+PiC+H}vzuyz0|#5NL+WVeeP434n4$7)S%}bD$0|ur-deMPD5NcP-(S;LbXxF3?WHG zw^Anpu0`aRSuYUk;~t%9uXvns&i^yUn&!!0%)|;z5i(QHyv_HOD8P)0r^+W~CW-M6 zLKlI{@y#GV7CG*0>gX!f(C{ZK4ilzpj?40wx7;SsWFFVL z&E`vFv%F3|G|LfF60pii(V1uFLL%XWT?*8-&s*opAY8MO`!5q>(A`y$;jc)&Bc@D67LBk z5>fT|C6yrx*k#t7iUMWo4!9$xhKQb-5Cjp1j98%O4eO>+JjTAK7yzZY&PCvQ%cv)# zK{A65%oHJy#cx9U%$+GMFt_*7_4+~_W;DP(-y&2K92OWxOpw&SaUK}tiPhhlX|<*4 zuy6?fkQL8Hn)nQp@X?o^>ZHf-{!MPRcQ|}K-DwnQhDTk7EYLvnxx4} z}{sw2i2rXVc#~4v39{r7UXw+f4#L>V}%MScDs ztVT0b-*^(=4~9Nw1+W22DW$WVP``U*VM}Ew>i*`H@l%Pi|762FD^^*$lKP8M?M!|) z{gX$2(H#6g38jksw{6ELB&&~sQz0Yowv=8R8+S0oo&MJ;bM&WO$b~H%3hH!g?UjgO zw|r=`9NC`)0%*qsqG}Xg@hr1s*GT=2kLR5O5lmG)J#B^idQx#+Y;q-hyW%2Z%*+9F z>sF{TU*1QS@|_v5DlzXu=cBV#5=DCuwDyg%fAAc(f9U$X?|d+12g-VRXGrC#`j8s> zcD9M|2GlcJZBx>oa({AAo(N$0Xhx<*CPvQ)||<2O-VL^+Jfc zZV}S^S#v*1Z-cFNV|R)T?~E<+3a#`;ExxQ3b;ZFuvps?QnNk&xs9BJ(ee)iLU1-m> z!s4)tf~$J`H1_UB`)$Y2*dFg8)QI{RbtZna;c32m&QUtmc=cWNU{|h~{ISq<9#);$ z)1PBlxuF}>)DQ`^y0Yj%N?j|H=?#w-h^g)9>4+qld%}K^piFht7)uUNUwC<>8Y>7? z)huGzwR2nqVx~AwufH(|2VHdoJON8Xxu^|h2)c0MIy03OO3z8rcen+M3|a_cV_YMh zji&7J3PtanTx_Q7p^5tD_j`JH@20^@OQ>Xq8>i_4mZGY5ko5gIo(LTA*B_BI*0h1; z1^Smyo{Ph2k%88?l6UJd9j?~AGbmt?a_$D(cQX_jyV?UDjas}1Msq*1S2wYJ!$mOd zdKMaVt&K^+(>APd7enBh)KG7Naw3@VSy?v;k6bR+BX;e3y({YS)8+O!*Wc8Y_e>!4 z2Sw7_$Eo~bN-v&g0MGO=1lIKW=oGJ^$7|nUi_J;R>R}O!KBwu@i{Ls*X!L6i{JCX* z!HN}fTZ(LYZ1)3bF@M92z3JiAXDlLL({p@f?7Q2n8=kCxT1JecsTa;j6@^8hgtclZ zb%wi69m>`^Vcaq$k3qE%*J!-U)?AsMho;iqY%b;ZP=C{;XAM+U7^#f{s@M!cs$;V% za*M!l2|@(Vlm8&KOqcLxl_MAuZO`%&9l7mxa=p`j8M2k|LvjAm+JAojY>kM+N4!o3 zmRiy#>b!5h;T-0y*my*nRDNC2pG!R7kDngo;1)>RdX<{{$BvBAneHDs1sDuEe?6Ve z_zxfyiYKGUztyby(*YXFF%YAOqS_`%PkvH?oV%;p#fy`QnX@}02uAY9{=iR9>oIpv z%uPBo*vt{-%y2vQ5-(C8vzI`ThpUx^SDJrzzb$fCcE~?m0Bq+dh*??lAxkIXJ8PcK z$V=EZJdL$f&uiO_k76d*IKun+#FP8>>goL(!YNhm&LzdpJW^2yRp#e!Y$Nb?wC+Ai zLKEy3xL+P9@V~PD8r%U}ler03<(;cZwWY1Z6n`w;QH*QJtk2Vly$M^p!6&G#9BV>O zVK!V!10LS0^N#f&Z*_Cr-$eYC(C;L34a?`MsSZxeuk|!;r93%41&5J#Q1-qIvr5mi z*HppZVAnEUWcY)v$!u9mUp9|_DewEIhTOWwFb!OBV77V1S3G#J=8@H^?SWQn0jVKe z{bT&L2eY38b4J1t?|b@5hq2OIIbcb3^ShPn^}Cv+XWDMjY+Y^)e~bsaH9vfA+ss#^ zjis#VA*~_yuz_b=N*S$8Xq05@u{`)X?J%y{jRTP&U`0v zw2FIk;B%HD8}8ZgV&QM={(wQ6>&me~d@7h{x@9&@Dj~}Hyr%<4Z^p@l1y2V=vIgbS6ecCEr$=3Y{6i;nz_m2VTAdmbpMWu=9Es>-d&SN|-lv`hxD;3Vbv5(bY zsU^Ol#cCg$qFXG>33o$MF|pB~iPh7txi-2WDYD~nr~U=-B-MaaQm1QW>>hRKs#ERZ zHqHC>zQfFg^$sKLEyhVfwM|S{h{H4+9;As0m9_}z2nl;eI{PevDp@|(^l}Bu6(?0t zQtMbsGX|6ozwE1ic5KIq?i#ZJ1#V^wP)V0<)yl6{7 z9GbSPk<>0J=4MlZ@a+x7RZ8zu5;N>tby7w_>Au5HtnbpEZF~rE&5Vzjip7aB>5U#X zMG^#OqgiMK?ivY|{;f&PKpOVPx*=aM2`A^xHefz#GU&Uzu#OKbosN7yQ#>XHqf?jm zr(|X6Isr{J!}7k#78u_>bsmAt`v`D2K!}U;4*NEOsEc1RQrnM~n+wr_)o;1qFAv-IRN-9#G8KZ%iRwvRJ zU{9|!+pI9Vg#g1YPu;uXZtCxUlThl!|eQPqq z_BWe4dFgFFSP&8vIu#I%Qo()T@wgK*Trzgy>AjnCVp&ZU2+pRU_aMF3KeCHILmCwx zBU6yHd#>RflQ5NT3&ZaX!T2W8(!YrPY^`p?NbP*pbt$?YxytEQ=Z;!Nu_)b>D1J2x zb}!=%t!Td`Jh!eL0Yg`Y|LiiV*< zSTcOo`vE8VGXX7g!f;^PYv^XyT&$j3##Xkv^{sL6Ge(p zQH<=l9cHSeoq@7AS!;7flzMr`qLaEX>}Rp;?w;1D_mx$>qA=(+`EmlPaBn$ORYS-> z_yz7>$QgC~Z&I`(Q-@DmrV4Lc7cY0w`)bc5*I9_}Zyd#z+yOz_h|~KZie95OE#~RR zkGm_S)?ugHeUTdHST<}j@>M1LC!!=Yr|kZ_nIDf~LAi?O)2Sc^>GEha1-L{$hfN+k zND*#>%^MGA1P<4=^nF1f8FGF@8VOIRw1GcPGhKd3`m=>tBT7aa{XJ^QQf;2=tAyWI zsB_!b8!&1WKx4ne*va^nng=}UvToIu@ZkKfjDbwR`1Ik^ZcM3@>naaYpi9-fDK#35 zoTtlD?HJO&zpeF6`dGmwEw4z>ex?NTbV8Q(@_f)T*p-Z)mNj((9aHLyAOiG+a$MdK zFps>{t5fS+cqq|JV}dbUi} z-IUB^q|>>|=(<>W#l}i>{p*k|IXF~7`@?F)c>Su7K%o1raae`pFXPc0tNGl56|veP zaQ*B5PY7CBVPkbD`I&(;8STEUpIo-U7ipM|j`3!#arP_!?If)hCz3U;$ zMxwVE-sJiQMhs-?;oP|1oJBUYX>q}?Kg0zS;WcuU5dq5$(om=6&jcg$Mewk%(7c_Q zI2Fa*YHE5{!^#$W_bU>lsX}x$XMSv)N`NiOg5mBoQY05yII&i8==YW#VvJT%=MQVo zA8Lq5a{xeVm8013w-`!^MPGZqwp?+v<|krpi9?6^rx~rXMCUw?7%kR9t6Jhp=bWM? z6nT$ujO-d6tD&bMU4Li8oR`u`ee_QdZR4pRFbTGO3%5r+1hzaQ>*ubs9z6H~oath7 z0E*@yg5{K)j+}MmT9CSFED#)Uam50|*0T3A-M&83_(|?;grT%OA8<=_ER>Z5|B0)2 zfbYma2XMG;Ji~ic?uE`I(+&dOGoL-2J>RWsx|1wM;qe>6<*tE9f13X|R2e0I?fW=4 zHb32}D`t{P9=_!nwCp)=Yt4`wmHak@28R4S;=X@5)9PHgp7?z%)vFs5X?cI<0#om9 zV3m}hV=)B@x*aViD_a`*7ay|P_jSZ0(lWa5k>8?I9^;KjpREy7$bPiX15OtPL^mX& zQ#d*&9Eo9C-AgrM|3|Wxad2b+81~9op~xX2jm#2;g=vew}(ZK2t;mS1>cNU4m4yR+G<-L&WN)1f>lpb#xoG? z3sbzB;rHk+IONmb;e&sam2P13GF_5W3*}CSJhas`YKFReHLzjXR~QY?*3VgOZ&rq$ zny?3nzP0X;hr1$yYvoYZwtDDq51ptL%_qGX9Y(R9r5&y%zf6w5>^c|#+QV<1HF`0t zj&HbMbIePs6JKRLjChDnWyEXPb7Q)uNBn&ZasB6H ztarifjgtTi&L&oug!J&WJi{Cs@pYR>bONb9md7x6NBI-;V)7_f(51JieTnpEA!?8x z4yJ^7HPp3B&1a8(kEb!PURlO;iG@a3&1pwAhjX@p?rr(KE#*c9*rn`uj&GP|PfUR> z^=05}5OQp0;kQc}N~jDH`b+a!aZ}CHlkG>lTodLvFG^OMf3K&UjcXV3ddtPu-xud$ zmooi%dz0XQFjWf-f*Jje0tb8lhk{^Wvi)2pvXzS+b~~qaV#u$2$@NV;O8l-0Roa*T zpD?w&>h6q;eve@*L(w}L-0sA;u~^KkzQIV;GTbtxi=U^5iMrq^GCa zrF90KU$fJnBUdX$qrx%iAD`z-nak*UZsuHUv&W!|3I}~s-_k%*mlAV)c&$$0BtYIi zO#`(Pd*5z(fN!hFc}hp4^IfH6TdVHhf(eZz<2E13=M@;PYFVwz??_(pJ-=+j zf<&ucFC=E{k<5>M+yzgw_2!%j3$~uqzalcUj``DO?w0UuNRW$C zC$PIYo=_Eh8LzsWz;j_9*d$}r<>xs+A7ltHtdQ&)OgyxjGf%3tK(9S}?nzC5#-6nO zvR=*;WZ6JIKfLn^>T+oGkkOI8WE_867-Z7Kt``yoz8#9NW$7Qv{dUbmb#=QLsY@d_ zkh(t<&N7-=uu|#VfXuXA?+uw$OT;xTyJ3$`&=$cM9cndp!7(Y_rO#aeX?VWJ2=*y! zWeg;ePQM~6g3Kc;Yg_GpnV?J!zuh&PVZTXL?$%3iQQF@@iud(MG*5+(&xu=>@wjU4 zNIDQZ=4}pu1=rFU_!0y~(LP*rnXo`#ux2Y1WT;7!@{qfxy}#kzKv0u4zr=1=9wnf| zc*tf8Wa$Irjy1+-oue~mTYrJcmM<3;eGZ~uZoAJ=lXgA3?3HTqeZ_#j;_GO!*V`#C zgo7{!)6Jdr2k4bXym4`{=n6F{eVbT6Wp!c2d=wqoG9ysk+w~?(lhso8`xd4*m~7ta zdOpPXv8pd%ER)v~=250{`;@U6E#?jz)OZ21c6yv-U zP3_@!E4$rR&NvXYu9DT(ah2F`UBMY8BglkF%k2h-0f)X2Swx)fjbP~zxR_Cw4zv{8 z2tOm`P~AZ&aAcM(`BrP91!y$1YkV5G*xQJ5y`n&0BJ|$0AJHJBov-&3!TI3UM=ZYO zEsxJ1AX+8tQ`Ob5IHr;=_TV;^5uJRkmt`AwdyJK!N#1bn)DZ*6lB^Bu=V}WL5Q^Lf|4MDTPRLk8NI*y z?m>0q$m0#wtvpe9!Y4zG!3v{!=jmw?h|n81`%7CL7iRrF?;W#}?BC=qd^j?tIgxMj zAHTRgfg;Chrmx&W&dbitn%F~81>|*}Brk?%4yo4hlcQ6mOH&UXj6G9R=Ca+eIYT~D zdnG$X0vI2*n|2ITE)M+nDn@q5WgC()4jyt5_1$FQX@5gNyB9ir496dX7`HoOoe zMdLbEBEB?G3kTD32=k30fuyZFQ@}gXrX+0c&WKDlGmFwT|D&$$vgDK1NvBvZ9k{|6 zb-xRq#xS&7!zmG!Vgp^t4&NTjh_*YET{zPp23Jxg2u@i&pEm!3j_1Ry*3)#j@c%;K zlK8T*ZI7+-ihp}rRs_1Xf2x&J5##+KmZI>#FK4W&=k&sHP5#JuJMC}}!6CO4UXb7M zr)~>MMV(udnkF1;yhpF(B~QZ*Wt;#pytL^BPQ19y&fHK@LmhU|a&hyFgKA&c3-P4( zmWJ@Vg$12FNH9aCIGY;kOo%5v6Tmk#TI0$7bj=&HID`# zx^eQyH|0Yn-8xP3Zz+cwmAA20`@;!Zx9E4Qa*K5o1DE2&)mCibhQCuTplyg$Y!$F? z>SwDFk(Q#<`5$+=A3(>rjC7qmUtrnYv~Z7y&q;q0x8{^^!^jzdV|LIMSLA+Njkh7> zao4>dR;V=gb1kR@>#Vdh54};EzgNIZOG&!P;xpgJ~L-+C>5X`l>LsSwAfcb5|5`HGv(nZ{y>7Tn<~Ve~)B|R`h5eV@ ztqSshTd)!<;kioAZox65@6JUiY0eDUQNm@YRW8Nk_;bLJoV6b=u$6HRG)m6Q694X) z4kv6TxiVmufU9e}ETWW^F|+RnT8hA1ImL-&xUxWyhbz1fR|HqBpN|1p4TrNNCr`9+ zKPY!(o;+5~dt_y#__>#p$sekGWF75w2dg+4>>0cmHz|{0*nZg&Xu1X$ZmPg1WrdVL z{D;&|sKI^D@&=Bi%kwFqEN70cVcfBF^a_(-g0xswNvHOhtRS9eu^cPxz=A`oK=!=t zqi~J9GG2(1OsTqimy!rB2;oEVZxf9OR;)a5%NW)$ok8NQEH+dxf|R7QhYAEAJD|p zmFoac&z@_jZRNYU3UR#6fmvgGWk+Vi}k&FZX$k&Rd zJfny07M?cF&0T{REHHY9J|gz3KyLGAgsa(h%w+Ifk-zovT$~^-P35h_slA!`wR6CK z50#5EBNXx*ToHNZflZXpgq6m@OaB@;7L~q2#(OSS~6&5bc@~08tC{#j`162_U zKZ<<(fKrv|6B2Urp~@>;xQYmwrAat88Rh*uVJ|-n8DTy?;qkcV=V*vGGAyVuUhB6& z`-)bzJqJSrL&vi=Rz}=`?$9AMhn)>)8Lcyn($keWnJ?2-o&Lun zBDp3OGay^Rsyy30rc9?T;8|FFs<=rsRk1hz!AjQ;!KOGtmH8wa7R&usqG(LGL_NX%|lvV^Ka_(w&C+{-ejEnJJR&YbQEa!dUq=bK zW%h5hm9Z^mJf39F&O4F`p%p5~r~6iIyk)AKF;+WRq#-;J8N|pFGGOW7dBNy3@}$A7 z<fs+QKz^x-%aDH&dD${MYO5X#d_o|KGl(wG;nP<_ z#bzDu+QWtB5Ba78k@0wAZCG)0j`p3;U8(Wu>IYLAyE|i`P}cCyBKGcfk2uvY2K3qU zrpKk+F-evV?RV*+VG;+k1xVPyc|bw-mmjZQ=?|0gfsOq^JV=O5wf#UoWeG%B6SL2k zJ>*lz4@W;0xq%A`H^uYLrRtiW4&8Vo?b|Z?Id}(fhh-`SsW%rjDnN$S`JNd^#RFIo zg5Q5OYmMwWsYCQ;7W+MTJe?5_8=uHp@{+1^yIrKt#h=|>W<-CC%9 z$4lOde^h8V%NYb+d%^C0HHA1SPZn|c#_)I`o#h4Q$n{-J#ymdB?ADL)zL(sJhjjCT zV=Zpco$qLnXU0QEou1Y#lO024v>*phNMJjc0yQM$!_Y_mnK$r`JS+kIUpzi@(ZI~M zve%A?Mqiii0HKHyIrVAIN;0b5Ou3xF(N-Q`BS)J`j?&AZ!l(N?{WT7goktWS<`*cJ zOIAx7b{VC>v6YJ<*D$1&j$v+(4JFhT_B+hh3}Na#EO43l0BIlLp=dvdNLtISr$d>D?3_|uGsRulxkkTQnE z&j^PzQL1R*SWm+0EkIly%chxCnW@_TD(K_==6DwVl%&FUC1>5s+W;FL@{XEWl_OYa zEJ|NuYh;lG;pk(x;So2qMTDf4#O*T@^@Q!38Hd7x^w_TVp$v>qv)EjzwSJXs zg^TX*bsuno@3mOTF@0hpcxH?@d>554X~ESa!d%TprZcffy7L5!>=|=0K0vm4^!_jyp@~OK=~;<_2YAM-2R=+4 zEXIFwsmn_U*Au-z2C@xvtao=??7tQz1CvxaC0AH1*52owHVNpoXW=H2>Vy&i*M$=uc>0 z=$0peT7<4lfsT-%2*JN;%O4&1f$k#>K3oQ-y2sR9qjZYTEcW~K7Z~_6^w-%{*aE}ikt|s0~t>lKi9Rd(4nxSO{-?&KVI7fBM_fZ)WrTRe9UR? zqPIW+v1Jv%m~`%ck;I?IHfYN&qB!YZO1nARp=UE4egjtxV_zZu%AtP$HWq=9dr#Pdn3a_ys>sj2p4%{Gb9dRo zmT#UEt1(Ysa>WqO!y5LdyKp1leY4b|;nv(JnC4Vw%M+MgJvnl*g3XlASbkqls2!ps z@*HF;O?c8ToKw)IW6$?~y?q)oGDaZ}%erXQiv*E-2!R8d6Bi4Zi=stl=p|!aFuM&d z%$LKW-z#aFgnsJC2=Wr~`J+9yW-NMwDAeV4Y3GR~hzvlBsmr+5hIif!&Tkl~ABD@` zP+|>&kfJ?eE(iYm=HrhZ_%W#soAS{A6V zVM9pl9vh*&P`z8QHDGZ}Ea3>8<@c{4=uL}vbj*)$#*{ca;ak=5^roMDrh}jxD(+mS>yRkX~2y$ zo=q;rz^#(CnG@^$GJTJQcDh^EUQNl$$;uoKSmz$@@U^e}6!Ep77(isf;DFlh9^XID zxxHiwttly+xPHsbk~U1pKBq97L>a$Z;fOVJ&L{_^7P7~V&$R4}dI|n;)(_O-_O$K7 zW!;^*6-qtd#m)!i@{Y-JvMH_{6@-Ut&qH?~pm^bp{0tV~+p$_@0J^-z!$*Kk+<)do zT$asa0~YS&$tlFx6I!@?mwRL^ilA>Q)N$GVl97LiE4)rir7yKuq*q z3ewZSNWt>9a(a4uzN#}1MaXK3ko5S9*Jer%oGS?5pxcm}=Eg>zYxx4iNpNvr$E$2h zk*aD~kGf?w!A{ju91Gw*lF$TSM!vG56AMAD)6VsL8mKe#(!HXQ{o30iP;SjacqdN5W z?m3$4s|kA-A@GUtVTg->gKuQ>M>Uf%@2)X#udEdTSBAQ>&;kZSN|jXPp1-DMYqsNw zKa;fEE1xbxp%dckgN)@CAj3LxIB&+oAkHAUFIg?TWUG(^h}|(`OCc6{rmJYe26PzR zF5-FV)v#rf&^3<;(2+S*>JktcuOj-FwjleVaOG2G9b+nocGljB<5ZV9?IQz|IO5V| z_8vRZNkpE@4Q}(fQBjF=&a_3U9Kq?c8+~_(h%N{@-~1=l`n6|D;S0dY(uo8fCSs?D zACP$d68luUiGQQ|jT3Wl={6s5WCynxf;kG!J^V|GhvZS1muE@;jhfMIA0H1+Ugde& zq1z`143nF^A}FbetR(m$&HV|h?Ac-XBu<{Y`AATdc92d0s;UK~EBzi2m{d zt@vlR*;|eHb%q#rO?&~WRY?6VjF;3sL+jqDsg(DDF+FOh1EUw7X1y;h@SyhL71)|qw0Az9Ms-Mps+ zt~o`If04&QPVZ>Y4+R~)(h)qR6;*)eMFE{IlfzFdh0G-B@1ye}>@QcjZ^)S*%FZ>4kH%rC^6}^~!WO!~PclR4eD@ZM2=WE?g&xKVE2f z;Z~E!QStuUo4Yb9H(ToS#`GF&#<rFIcb)-b1tEMnzkp07Q4v6MJ(nzD)y#upwQmLje_TldclOr>TnP# z(Dtbt#`!v@8|phM026sBy`uocEjrp3hC|R15qt|;lPZGh^s6LFT(UIS>sXt4+QUV) z7bvh1;dV&1JF}xo_P>gyPi2#lIUr0ph1zZ1F;h1)m~ zkqy8t4_E(uQgC%6TYXGzo74m~lNn8g;Oad`oKKI!^^Dx+Oc+#(m_cX%w61sydiNF~ zDzP9A$BVi(9e(=9nbvhk8I*B$O9S&3l*`S<&OULGB67(*la4ux+0UQg@=b~z)_=w* zTSoo@FB5Le;~LgVLTlM)ebLfnSe->Nndb>5&GWtCs>nTsGVw7E4qOP_!if=CVewm| z!Zv&?wr%5w^)+-}+PLFfGrTl()KokOx;i8NO7>`ZTwPIwpIEAOd5xi*=^3x1W6lX0 zieV%(+b?&;zZlu z2HM4pelm6Dw7_17cV^YP7aG14=GK<&mAA&?M7WFg!;ZRXm5uG7qMEfmZMkJU6337{ zO}t!0=~FxrW&7@BAJLs2P%a(&0+(nnm5RqH8+xiv45Ds8I6}44h0Le$>2;!9h#P?r z3T#(2SD+gSLG=M9h+G@pA=qv%GDSMC88%{PF_?U_VLDbY61;li1eYRdmhLb0OuRZX zmb{^Z>asYJrEM>1Zgxh8#{~F08zs$GKC+c~A8m!vQ>MVDDQufhjAUx@t#q&Uk|#uC~Ll<9qVa9p54bD%~u9a6hZ>L$UAZN{bBNtO_D{A36Np-cpkK zGA~{J2Fkq9SD#_9<2dXz*ehwUqRq#f z))NRo9{$-4XGnAuJD<3Igb3{p!baX9Mr}0WDDmLUt_Vy$dB+=`>i4L+jm_lvCYB4o zQa^)~o6yI+9{@MC5Ua#(fj$Pvr#I`vgH8klE#ty?8MIdl0bo7N$#Qf_860+ETew=F zC2tU7BK#`#mXUX9751QcTwUnbEV=rwGK6yU`m8}f?9!)eI&7D>UtNas0=N7+kH7bm zY8w7jM;_UU_Bf);I+HTEkxCfnF5GRNvRN_ZQW=j;8IK^30S!4p?}Hu|w|YRAC;tM*RABCkOD+;xlJBhh}i_fy*T ze1%>Maq8j;O!ZemL*c@vx+>FAz$aF_$H`8N(c5heBC9c{Q!~ZLfc$q6W^CUhKG4|h zjywZ(*X{-)Mff>>7HI3HGRlgCvGKP7-YP@kij4r!c8xM4WBK&z9Nb-R-;%-Avy&HM z;1c$-=!VPT8bMo8SdOUvYZ?8BBRc`6$mkXQw4!|vMTgGAitda>jNX1_a-%m&&`fSH2V|saabS*CK5uqVf+Vs+y;u-8Ifg5`R=~c1Vp@$hX zRC8|ra-Eg{XbkoKfCLh23O^w>8|W=$=#$vA%MZ`nP1E`Iug~Za*j$`^^nyjVi>p$r zs=?r?m!T6{_77~eD*DJX-@xQmu~5z#=Z5KIeMyh@bfA^IgHL!P&Qh$%-xNW>546Q~ zvIeY7iORh*)_rvtbY^Lz$HLmw(L!Nq8-6vcccc)b#DtV$>xdA?-nA zKP;?S>fIR;7Z*3*-qIs$aS#iMg;Vq*%igm5li57!9jw(@eicdg7>ViNGF!aqez#fp z4`Y`n-At)QiDpxS};f^hS29Nn7M$+mFeZ7qBUxLAV!g2!ax3n(;HX`h(0;2MU z{C~DR6uuR^nc^|8KS#*#_(6?U9v4EswP81joNK1b?F7iclzBTmjWxGiqIKN1#dk@X zu76ZGr*CI#|HWy<7NKc2XXYN_kKFk8KeMJ6!+TLMAKbj4^0?k3B{PFsZo;rqY{mgn z6M!UJZHO6P7Jk8tpB3Lkn`)6D0&tj)*CK=4X$>w;)==Ml{KJazL)jvc5qR?x@>=jU zp+11K(&Wy{pp4D8)r8?~ost3%dulz)9q2CG5qlzY#;WMwwP6cdhWO3T*>>JoO>?2G z)O{yUdz)D(UfKcPK?2=^3tJV|bdOf#wJAg}Uh(I{gHrfDzWavAgvarV=HB$qZS2iO zh?q{P!2Uju-g)QhF&F0GSVI}rItXgp#Z?0*`xLLI^^9gGA@+k`t{(_UkYgl0qLg1uNix;|>>)?TTxvmzuWQlbP6$ij9+!C2Tyi~@kOG1Q&c`pHP zcoN|pc82@2?w(|u6i!LBD132uO>*=vg6)K6;DM`HHPu7$MglONPz3$qPtn;Q0 zj+cHZQAg%rvL#PlpAKC%@EpbE=UQMig+qgBAB${eq{o=Hm8IAJ!2F7s?&<`0S?_H1 ziV5#jlwnA3>u!>&`i!dzNS+2-v|q@F{VTs|jBpGLH+bs6ri!%e3=%lIG;;PW`u86O zCwmV*Ai|BN&~@5EzqTiOQr4d8_rzYazij%pJWOhrLKx6~s^RvQ(#By1@j!DQcfVju zf#&wB7QFFO%xZ9_&vlaFshT~u0JI7pub5Vyuw()9VV=dbwu+wPNtFF-`#-G7WU^F; zKO^+Sxf-=mJJ6=gnUf+fxOc?ee3(918xAGVks+g*q5Ly=;9+cNqiBaIT!g}e2`{}W z)$#S|!!Uo(LWtJWU7`2KP1%~8 zHEeqqVs(RuqBrUUS#hvi z@Y6=Yl=m*3@Ao8=h98d#sMc|$(p^nWiqx3RG!V@sZkJ^Stl)CHK?PV#Pw&JYE4Gg1 z)xUjQIXw_^tS4(zO;CEn{f~qiym;ixz>{==txgY?lVn8icm~PLll)g{_G=w!mCFiQ zs-cALLKr&&o#BUiRwRf~4??OWfrXOp#3-h?Dk6=o)*=h6i?LWYwqMLb@cS6E)$EOo ze%p~Rfl2KM{hjgOpVARWp2t1!Ele>KtxX1_jNO0Ei*Mf=9lrkcHvl7!qnS0Z6meg~ z{Czer;IzoxEXXeC-sX4Z@o!#c4@)g^u$tH!&q5!CD|c);0s*>LS{lkYibqklwWmMZ z5Io}nM9t?<7dk!(^P>L?+8Yb;7wZQ%bzauV;fhD=Z4|OnxsnPz*eyUc`d?=X909tr zMn0U2*V_d)_E&Zdi|U};edWJNg=)dT&ft zLq#_QIbMqlfEO#lu;Kj%=3T}+-hT(XHWk;3g3~wH$$Z)0n)km~lyvWZhU`k`2SiY)BksDzZixaAZfb)TV=Y>_`=yHf2`m=QTAaRjbH<8pX1N$` zU{#Kt_U;d0p|wpcEmWGDneM^k7&^bBVxkVsEzJ2L)EASEoM~+_je)d~Vhg@(_`=Pe z*0>u{N9I~rNvRCUFY)9SS?vyh;eMPIVtzLTs30W-Mr^1T%=Nk#-`#A^rl~Ic!V_6& zd@fyYPBi9E-gMLM1tX)H{~6F}lIt=BQK(Ua%^B;=$qFDQ_K|?`(A%3nIj5S!mp?Zf z?mlxH*k69p8!fVO$P=n&+_dCzE%qMsiHfp^!I3)P3qL!8S8&! zIGj$veq2L;KmbN|%FU_sl}CyqdQs4nHzYGL$V}5-lMM3=c=O}Dp~l&kNlN;lU)^tR zAl49F=eQa&?T?9XnPnK$pyqRso_Z@SJ|IKP49a&M-0Jx3MBv(|tv zSX5&hUFvShA^X7Hg?1aZ51>B1dfw3$TsNT*&SaCV5W~btd-gwk#U5(-ZV5P2g8_q- zQHD+IKq+6eG7XJ^6=MnZ^IZgz6~@&0cG3J%U|*wufy0G(yVFiW){!p8{@RK)AUm5Pr;o87r=(AND|lXi}8 zCI*H^goY(Q8;o1roQic47NS9}W%OU(x}v{3m(xtXX##t}tW>40jK4q{v#|mPw=<|W zeWkDAFG@+nWqg-;pW_!Ru5yCUnP41#M4!&aH0Qhbkyfnu@N2iVTHuaUX4Ov@TT7^= z$(6D@ZyZZdgE7h*v0Zo;@*Sn)A0OwhWv%ly>Q9-*)%u&e1sOdy5aRpmwR*B|ov%XH zR(^w}sdVYEk!@Y$1<8y$lbl>~6?d{y@x5b&=qebTn1y`0Fi?g9SxM5-YrTIK>ksBR z-EWpl*Qa5=IoOVt$SSu+Qju?3OTN;^;qXtybi+m}7;);n!+#nj!?HpujLb-ZLqbZ- z6;r&{iPRkq5l(fv$*k4w6zfxUnHmI=r6^`}Ar&&afn>^dj@1SYZkwIVR@9x!HAdGE z;6oBHKVhmQ?tUd4X8nL+<29h}c{wa*yO@eEysY|6YwCB?0BN?2-gRoRuPShScRy$!iQZ%=hbz0lKENyp;B6fUKR-C(a}X`(T=WgDz<&- zSjv_q2bR|FE|O>$bj|p0H8c{SXw4@%m0EQu34w~0S{I6bDa+G<1jBP~Hs)|8+!+RR z%#E2l%IUEsJkIrflLgVigujPCu>v51y27PQf4)vW3auQc%*9=qNSW)w{D?YnWM8OX ztKKIj<$Iknv86Ku_Pk@vcWDb29mUdJ5T)w*x1TOha-+}$le zfZ*;H+_j)^3GM`UcL`9qyIbMz?(W*0d;6UGd#_*j=rQV#U86?rnzh$lQ@(G`xo~8Q z2VO5#Nfq_6!HyGyQs5uT>Gr_-n3&YSAShE<2r|gmqN}5{=&79FbTGS99_g#;(m4G# zn>$Qpp`L9}rAg@5KLh9?HOY~lUd z0rK>?2)jt3$Ot%|89bTuyti(<&>d>dc)c6Gc>lg3eOdIQ|Q{bvZ!vTLLX3*k-D* z{tLaOz(lbBbj9H$Cr0w06h^VRG{p^rPBXMPdiD#H+ti4)vNJdnKX*zH`ey!7 zY(>oATItUP-=uX2slf54UiVX#n7CtWe&;Tx#s3E8sw!~AkBjW!-%sBnLy!@|U=HbJ zxPRuQF^5lkJo7II*rR!PK-qgVgvypO@Kow+G2=>2?eyN`9*8^TozmcG5sEcl{`)X* zC!5zAo&2iK%K6>ls%tr3%M*1;sdqU$MYtUi5%bkLjc&6yMW-7dvEshuZ%E$8RfS;*Xv$NMiijK zB+%7WWH{8QSn*P$1HxkK5cr+1q z&2p6Z7q@Y_Ro{W+IuN4=N>}3wk+7*O4-Jtk_=KXdvxFT_?F1QfX`t(oYchZFe6hUBJgIAI{LKU>SKbsA zKg`In#4Yy>+8ZF7eKh3w-coV`!}b4kBj;Kt5I}HD9F%|`ENiJ~SQG;)y^|ELy$$TT zRdYxb(MAPaf!fg{dQ;=?!#hvPi|IvM_r1X{%*To0pt{Rrb=EcX@sm3!O>_WFt#P#O zz>zMP<&-n>bbB5nMO3+KaSXmMR*4y-CvDQu@6g-W!hx{=T7~&HU^W<-g!B zL3wwP&&yF}x^L~C>RM4AkrKx|v4C$8Lj5wk+X?%Oh(QUNlxY|9L9D#MZ$=V=LnA#_ z8^&Og!=G@{^{@7)&RTL>OImCAFOc=~uv33kx!fB*NvrWn29t5O3LRcSWG0GE9TK$S zbM;ajbMv()kCivv>8?Fj*RtPnt3|oS*E($DvKGTK_@z$$7^Ap-@Rln`8_Bru<>yn3 zf_dVm`C)1`-@)}a*FG)I&k}^DWNoZWHVcyqnZ6Tb@o!%qFi}#=?DsE#bK+eN5-AXj zEJh@b@KlTo8Qi@umXuZNY&)~ZyQ9BCKeNQ&?k?~(E-P>TYgrg-{h=g)jCFPR8co`@ z6-cnY;)P0lMsHf)oXI}_`~M%ndDRm7Z?~jqBk(?p-`D=OHh74g6>KJP4n?V8zic{! zDQ&e0po6}bY`>_&W~}Sp$4i2V#o`O9+u@6WBYnG#y|(s@LuAlJLUNq&LM(8!+BN)@ z40SSC3(5=FFw@3{Vq3wO0-U@scKxSyTI4`Qj7u0@WQF=$jm>C7*~8+^8gl!~_#*q9 z@xr1pgB$*UG(^xdg`lOP-l4GW5R|4;6n#hxiB3C$dso$_Y{G?l8ip z>{=Z7xHNBK{{1|uh^4$iy=%d%FK|zue`H4S?@02&Oy~v+nB_n%`WWbs{U7uWj`YWD zaWh1*lE3Xa(`HT5dA24L*a{p1qPgdP{w$EjgAMatz?{vP9Q78VS7GTHiNk!MjrgmN z{^-tf8wK1y>X>?E^TR%6f1m|#Om@gFzh*BsN3|SaJZ6nQTZ76y9l7mnE;cX4&RMgC zOE#7M@%z2V`BI;q)dBB%%M?0m6-gt4-YJf=hKU?%lygpY&02DkiM7Tp+QGaR%v+cy#WZ|_>!f2{I^c&zIV zGEtGiNy2Z=3yDwWCJzZlp1wuPcLS@*82peuurFUa`?;}dBu`%$_d1%0>eiXh5NXYr z6#C*SruS>Ot=aI=QNE;NjV}>icO*$v_3TS`N>(`8mV_!syC`a4I(27 zp5~!u9}ILP!_pUPIdUf>8R3f>oS?!nbK{>RhU%V=e(`tH0p}4tUkGIUw?sb99vIJ> zw+Fhk?S+A;2GEmAHa1U5T@tbXV`n~!_f)(g*qP!+J)ybm?zgyXnGHMrX0@cUBxQS| z{7MtKYKwhyeG4(y$&~-Qh?}hDlkKSSfGt$PiW|oN+($$uei+qP%ZM8fTKLqD1^e1g zTZWyg4noU?-i=7^xa*Z*yi#^xEs{CGY`GA|=?K@?#OL#5qT$>5LcD1g-T+GPFFLUM zKUZQ_X%`G>8E&$in#a%a2HEUkw*#ITc{W^-S0|&-Y!y8l7(t)h|HqYm{Iyc84NysjZ^0#u-XY0FGvG z1H`YWY(BVA{tW&P0{F?#S?^b?bMzHkGqI%8PuUeI{pXWY@5=wP^dV`&7GG6p#S#&q zdv-B96&_X;b__nt1WNzI4@{LJ&*0bi_MOj}4IFf}RkknUTq=6K@1(VIyCw;y-= zJ~LG&97#tgrY*%o_;kDhJ0mK zBz|l8bNQyAYBCRqXsb-f;zjP%H~Lc zGMz|rB4$P!U|YI2b2^z6^Gdb3f9T6V7W%bC?Rw82uwZ}Nn=wD0DYuow;K}k!aNSm( zPEdyaKLPFsMo+4$3xUy@DYbBN57%;1_jyjvHM#C9E!|h1ALAZLgTqVd|8{X7&mecI zSTzIk9}gp-QSbi*Op*pX%qx}5&Lk~sajV6lex~*AYG0Y0DoNehr_AA=Xf%@LoncXN zmJ1-N?kJ58Tf&~T$x>^032}_I+BL}+2tV4;pGL7ext7Nqg)CLLo_j*Fv}@NeXi_YC zG&G`|y?Z+@rMpK$%nvl$T)*Q7G6;3m?_9019>UPKe3{=8=L4qmKZ3sq9bxM=l(RUD z>L&fJE1gsBBKTx^wID#Gao1n%WOr7O28Mr?p?tAQ15uecQWhn@t81iHl860X8f&%4 zh#Q&nr>G5etlhV=H41}#r(CNY9Woh#w2k1@l8wF}DK<@A+X@^RXYV$&;krR4raR$R zn*-@2R5-L!9h5sP zZTg~HdciY85?-o5or~a(d{r7`Ua7%IO{_a*+{J`33ORPg!bz8Z&&wrWLMNBi^w10h z#?c*;p|3WpeuWGbY-eU)KXKk-sqfb5SdW)(h4f-Lt9#@0v!2i=BO}d5hJB?TrHm#o zdtFpHox9ueLpx3@_D4M>58XV%szG%T0L2FAItQ;pNJ z(J47B|C13byiiYmm)X>eB}-IMYq=}D{hi7){d(a^nf|$^LP`zcb(z+|2a?*9S3oDr zmLoowLE6Vd2C$V`Njq z7-1Q8=Z|hoR`c*==6ixoc`DI4S6P^)kqOZV7p;VgZAS~tTd3J$6hv>_<3armF4t+hl&PaFqYRB_Hl zQV2!nJNp_#uqsr~by=g*)O@~22S2yf1f6V8!;%z9+3tq#_t5K~$Q8vZ+oKqrj!*rc z53Q$8pdah-F|XvZOuUkz!xv??IXMp8qD7wWFMsSq;lLd!2DcpVp*^|KPo}_pTAs=G zScfD*2rqwgW!3WZ)L4phmr(N8Y)JL}LGBUHf z%+32B#jDMfZBI{e@7ES6dMiZ;Yhy2m>x(gf$^DRp1aYmxgqxMCQ%ZqlTEK@U(3*ZF z59+ICd{TlMA8DP5rM1*Twa2`(ZY!Q3kGM zOQG&+b?8+yQqt6*8y?YVxSLX$i}Ej~>*>o&!_2a=S6gPf=3Qg6?)Fqy>PP;u?mi~? zbg;8yGRS!eWFF&=+?RV#Q%Y$0uOU81FPpCIk*X~7m3?G{zxL0~LWUaRQXJfxkAO&O zrfEsr$1sXrS=tqD9V7e2Qnz+Oa%GGVTA#|qpj4YI1tG;$6;6_1zkA_%Y{dN;K37D5 zY*K+!ylpQ!;v}6CawGM-Ki$X%e7iqH0)-)l?!$z5cj6H1(SlatJ z?J+uI|8X|GuRkIK9^TItub@+wNAu2FIF-AI0y1RSJFnJ zbtQtEkJ?-fzerT>Qu@bRUuM7UZ#^g5W8v3SltvtmD*%1(x%9^Ut12_O4u?{ujchZA zOF>YLI8X`;jZ`uqvmWd4R`*Y#RTW};1+9j4x=_+c%*5yVfu);*Nsijy@2}dghbt2i zN#STU!eo35Y5qB83l7~%?Joy8WmNO8y(i;>Kqo`%6~a^VG88&3C_ev1(tzBBTU{3%N_52a!yo9 z=svLr_2A20&WHK{FDI|)$%`;NeI=!a1MwmcmKTuEFZh)v6e|!_Ri@KmVV^e7D-3zE zWM?wT-vnced>&%fHl^L~uz$f75B=GEYvlVr-eiq(#@iDWC$^Mhm<>eKZ)SJt0{4U@ zW{iMB$T`o!O|FD9E^-sfoLpzk9h8v*5y`5N={E#XK~x|L+DcDig4-Pl`KFtlfrIZg za&-qQ3%ICp8P`KtNC-MFnYO_F-=uG@66wZ66^Q$SfiMkRxjugZo*nEdFVYKRj z=>ya)k%t0_bfuApn(~^@($RFoyRW~dyY<-dE|;S(rv<~`t}O!z_+XA)N@W{J*z_u3 zB2qJM@@4LVDQl?Srr>hI8nKf7Ew6VnwYkHpif)YC{DmK!!tx+z^K_sfz`BvY1eNR*Nwq548 z0ANTTgO*tTz!C~~V`A0Gf3F!;(eFOADjwBU`&Et_G_j!wx@A6!H4teB8 zmf|zFMeG*oa&_E0^beY_4ir=Ni--9u^{yQhFCI_5lZ@N79HLHg-&vag?^Rkm6_I;j zjOglnb+HVeQjjG!#O#&Lj?s5jVV2YjXa5@v#MDyXKJm3aJ1bK>*c9$IuJ9Ft5V>-( zfgsa*ssw`G33?#CucWF%_J!~CPo6(Nq~@2L?0`|buw_?fu#r2fRGL-z3WSGi1t%`a zFJ1>|pC#t9C@KQ%3@N$Hv|wAZ3kv{OD}mUm1S*3g46H(d6iERp=6go{zjZ23m^HWR z8DTgPr<-sbs`ld&a}tL-$nf|YK zX@Qh3T={X~ehh3$$*)5%gel=?R%I17hb#KxWaE^Po_!(V{(Rh(fdNcQ5?yf>tzHIb`CX`q0?@s35mgB59cBC5k+KRUe za(kC1Zt{l&z**8YEHvV&t9rpGeI^o$mscNpAKQN6-%N?8b@j&E*n90p6IK4VX#nXs=bB&nspDSV$=;CQktv!`M`3T^Xv%y*43{pFb5 zAW#(Lhz)%}2O z_nqKMzDmvRmzq5ObX^C6bZml{xjD?C8dRP3)6_1b5UWp^i9U>Pn9l$&|BMLTLsf!d zPg6aY03YnsfTN#28RF8POn@Jwo7<1T3{uwVFlZ=_w5O>ub%?~;ZEK!9A6fUM)=bBQ zj4VGiA}_oJZX9%Q|22Z%Z=#hW^;(%l0_h3!FB=iTvC^q9#ZjN1N{k0g0QCfsAj4r* z;e8eX8<}~Kj-rhW*xl)bNkEDwiDE!2>e>>TkS{DODT|H6aayB^B94Fd$1ebJ^KF^` zNLZY;g#kD-Z+gi{M+M{M?TPnhws++o+nfKBIVFASPX&x+Mm5%rPs|mcY=S5 z9aU8_X|DMTxzkEc4Gh3xY~&m_`|ZE@a;yv`ZFaz`t8F|_M(FT&2*UueNoORzW%r7g ze{ML=S=t-h>fChSg%+SZPC+ftapI83hTZqXowYzPm6ea-p<80z60-`?48i zlJhMgm=Y{#D{Eip^D%%#OncI$i~et-FBayX9IF?bujsLhrbmY;-Uw=~&SWzdFy6A- z?opzTc~M(^?&Tn1Iw5dwq(Hwh!WYQHWUGIKs^u_@)bGSn1Jl72HW??B`mKw`TtmFt z1pDFJo|;s8mFRuIt#5oF3gvoZ=c!z3zcybInlB^}x$}p&Yp+lw@P3`6xEqGd5bNvL z8!4o&4&xqcz%`GvrhDLL83Jgz6*&^eYm}9EuSg?0+O0OetILeDjR+T*0rD74m&GA6 zVf9Y(qJCk$il}7^W(?-+Zn;bpNXL@O$;q)khrTaUV=ooCw+Do` z)VB;ZO^r18aQeBlpGyrh86Rs=K}l%4JGW#lXGs&R8c?~p zu?x~-LcVlhm>7r*b-$YkeW}y-SZ_YsYM3^~?k0HjpAL1eX^X?(DR<&7~ zuUj9ke@w_f4Q*KQrJZP3dHRW6K{mf-p_*dSm{3#~j1K z8RRaaLo(<^m*Gk<@mHJf`UF%er(j2QsAF;2ny#}mdRu@|M60oPt+v0WvRV)l?gX3~ z2kKa)>lcqfOAZ=G4cqHwclpuiUJIZF3%BE%%>?JR(GLr0 z%3v}2Qidesakhl3Hl)-7&C7LCMrbNwVm@zPVq+#SGG$k}B#&$_W4sc2!vHZrxlX>B zR(8v?ji&;1kEGq}(Js>Ho4gERfe7i$Q-a-(pgm#v07 z5c)6rv+2P>;-A`P#0pk}tnQ_}UG4**oRP#%h-=1t7Ym5rmnmBLak9KP-+TKsE{CtX}cJ!1ftqxe0gD?>nSi$OZm4x1x)~ zB2uD)cP_=KKPiBF%Y|Iv5rnz`vF%g~y$t&6+0|)_{n<+)&Vi2cf>FenAwa>>#NVNm zFm$b{q$7f)FqtQC`rewP1BfJfNas%%LBe9IrL4{mFBTCVlodJriULL_StGZ$jKXC9 z)?e{4JnchnrjKUcgYD20_I_XRqVTvzjP$%6RrV)WZ7s(wl5@C8<3P(=iQEqHs#hss zRlR5JRhW7TIg~qziq*9>=lqN$Z6vAr`HO>UZhz5fZi{cDmtRQ*K|`X>cH%+2((JVO z2sDuo+{~*ZX&(kr0cTwynJ$ARy+Z}OSH~E2iW&=H_}bHY(T1isUb9`D5?~YPd62i; z>(L!2m#KWeTTZ=u*;dfV=zQ6u|8OZAGpG_JNeiHs`+^Vs$eRrB=?#JZ_{bZu^%=Qh z)iNuIjr3uZdktbihtrWgJ~lLGY91*BT7nUaJ3{a3I z^UD+)1_yVy&+L^zS84E+4sr3$9-i+RX7PRs zBEzEfVU%6C0VqI6hLhpt`TiGT($&vbNX|Ic#+1LpA+G3@mFDf2=^ZNzt!D(>!R znL0P8t5I-aOtQOe3Qej%vd2+l19NANsBUc(`Gn*3;-mc|l8XSU!_aO68?_tcyufo(1JTSk3P;*w~|@vV1j>D{97( z0cFg>%f|kG6KIt?-U;!Sc|AiyleiZ`2PT)TOyY&NSPJPU+y} zm|jC{B=xS?8PSJJ5XQXI=61>U*FpA&OLhL7upx<4US`6UNY}teC=uAZkt|y#&CyDx z7)1Gk}n(T9aNS*R8{!a6ln_B}T*xKhX~5D;g( zDWz^ox3>~usM*GHfBk{QDupoxJ`Ff#$#WKs3ZG>#GESAgsvKca2+3T(7&bSNEV?Pf z0A^ZuW*7T^Q4jwb6dnsQw0vq!=jM}=7bDd^CU^+`7I)^WT9p*I&$lQ(cM8!bvw^r@ zUBKC$BZ?*?x-F8{m64W?L`djytmdr?xjXpsdmxh5QM8XhBegVI-NoNL2 z6kIYf23fhN*_;#d%_kt|&+k1ag__cM@{Jgmit=Oep zDihy*lfaQeY@=|1dYaz7jNMijfS)KKe3+VQRSEO(&^%P!n&Y0~F_h|xCY;rYK_(CP zCXXkr7tNw{p1Tb$N9Y$QL8$4&Y@jm@KB8f|g`|;AX?x63GW$*3%vmX`*;nyDd6C{~ zrxjay9sq8j;NY*pA1+HY-$oDTLLKpukOwB`uxf0a{pyS5&|>hTCHI7APd~S^b0%Em z@L9PH;$*ww467x8{<8NUdaZ%XARk-PTXlxXw5{Aa2{v>q#TA`dW_fkIJS$4rR;s2r$z!#3hjGWhkzv2m#9tM-wr4E~0S zOGIN&AiixZ*&18-(3@fXX~p;HPpyt_D4EOo%#6oZ$<5IektSuHG6fmzCmdGsS2=YH zrTiyam6K;2GHEJ8_U_o z@^61zQv;lg>wk^U0tj8NoE)zP5`Q4@^TdlGzmTzX0~8*#)a;B6^~R0$r7jB;-Zf6H zB~KG3SIYFBOJ*1>y_26_L~Iy;ev_vJsEA*eia8kkI3S!_s3i~HOY-~-g}2{K=jznd z-^Uh5%oM+*H@BO0LiUXHJrZXP!rXzFp$CG}pFuE)D{1RKx=qtzC{_mtr@&4rgXkEQ zB|8CBKHfi6pOzM-hr9FBh4kK*Zf{3EC}m4AJ0g>KZ!3{sO;d=K;wBcI=-r;CK%I#T zL+v_L^$YiM*Yq>gJQmZfAr%qB_+w0ojsn%dsp0Aqx)h?*jjP|}Z<6!Y8E}jh_-=~2 zB`-0$q5%yDdD^)ti#VNVcNhb;M|vsAw5YWEH^cf+k381eg?{LrZTn?6HEDuTyfKVE zfJ+FdV*g%9OSJx}3zGQRXK6t5{gzW=-03pC&Cg>_^&0dSFJ_X2O8;zYV@J%6OiIEd zz!`aB?qjs;fXb7U4HKbRW}GUr*opme6)t=$lrT!ihdkpq{RLb2v;)OQR87$(L+LiI zV3*6)Kf$N?;S26r!Je?aA}sFUd&hQ;?%O(_xU;VU1T=q*d%WtbLk145j&hnf98blp zOJ1m)`Ctfxm)r!EhANO}`Oo||6ny)$ZXF(umPy9A_ty?OL3w_EUFIEw$9~oNoa{o( zpSdgYnELU16}h{$l!r0g&r~y_72WHg?la2bsIyKTS=Cb?z!I*S=6Ty-YOipf-~@P~ z@kTjc?)ACio%%MEq&iYDQK7^SAtKmFz+L8EC#N8gXRw{H;%`J1e1@=#Gs?wQ+eW~yL?)AEIP7a60q>zHbRi{(N|or zp=xJr{IC6Fd702$QM0hGJW7)?+BVGbS86qPC%6R6G_&WovoDJ~qKG?Irq(Cs*WL~n zMAdtE8C+V={&=yTC<^WzyR{s?79P2hzl*WX%j4WsHaY>iAy-BEG{`=HprS72_aE*< zvwT`;>~{Oh##C3@;-lC1w)unzesx~O?KO!pF>I@6+D~8QajqT7t3Lz^0ELs0(fQ`G zn*=;}l7`{ipBSID3K>&XqK5MM8)$2;-Gm2`v>f1xJ*q?Q_LsPm#k^^oOn&F_EWG^Q zUBN%vI`=-Sxx=y){_@$tfCTUx!gKSGN$&BP$!AZ#!b=Fv^Pc>|jRc{W(yM=aGyQifUy*jK$3@`JHCrYVM|k| z@xy~jyPJ6_wlY0B{oTimPef}IBBIsfoWYRk>8XL}^(*lC$T4fmz`x`W{t}=a>(&UZ z_i?F_ZoY%fH&i3v0g(zPj*Gx}m(k)!0{4HvRz5L(T+)lkd?JhCaf_?^&j%!<7;gM2 z|MT`=UkFcxZiXmTt}9H3oom55f(XDR1!7l2UWy8T!Qzb_u$6V9RZjxEH?PoxS{`yp zsB?HM7PPu_Z|ffujj@bb*C-n3U9keeV7A;InxQrA4MLPsD@W$1mm4{6)(+D=cUAaf zQG>fIgUfcAZ8c-i;;QOsu#jTk)Me{eyQc2-*A)r=RipAFy6~Y&I+Oc)!y^G8fw<>KU0k|}D~*j96Jl(QX+HQYv! zkjg?Q-`~$pV@|z3d$G8wEdV)(xr3W;%ynuIzh(~n>0{j8AhkP68JEYP5c}w4RPPLG zeVS4HmVoxrzIE9wHuE(n>UbU4EKPP_BvbRie(o}}&-hdfZB==c3{|~qIO9Y>w%gEX za#7%9JAt_N>aW?dTaim@ZJuLR?4y19Q@Ul1ayP+c>r|U7W9?RL$-6TM%z!@Mluo{M zh%vcSr{xNjC{Sr7y_n0sf@w5hbAe>v!*(n%6}QIsl#!guzCGLym4_v$ry!rWh?m_k%!r=sgAbwE3bdG41tD6V9;}=>Kk0jmRi)kHZJJ-?~q}= z#~p+3k=u#4C43rU|69{-=&Uv2d*wtEO8cd_Z|_5gO&zA^mhvnHFDX0v&Iw;zs}~Q@ zE4;!q&s3M^gHljdH6B0;YI16h=8_NmX_Zt#mUPQE+yqDo-_k)QOC(|5+O6~QsudfE zc4%@tH^OAcSR9&^70DxI%sepi0R-S=Cna6{hLtL&n+bgusnuaA*2$Dt{0J3abqUO) zqiv+?f0*J+pI4YZUlH&>0v)X>yEaM8@IBmGZ2Y{dCHEqhbQOhY^Ct|{a+jNIl%ZSZ zuoM!_&g(#X6gJwI>7G^`Ci6(pAG} zAHI6$Gu=tuhGRy5^(vhkeMeT&edL$)2mL4!qUTwuZl<=85h$@mmt%Ll_L!N0sROGe zU@bwtP*Z$lTLyod55JtX?b`bx-W96u)}k_t4Ba+eAU_YC<--jTwpmt7Z`xPJjri53 z_##g6$3r0(2NtQlt#A0p#TcjNkG6N-jX|a3be{Ll?;6&P2(AyITBX{24`G8mOJJ11P!TnbAXIBCr&v^*6Eby1nrSyzys9&tdPV9z$(4gmXGuN_ zoJw9V5~A#>1F1eqE+%z1IwCxFQkBy1c%|620dCd6pvR}nVYK#ZYauTwgr7`QEsVoaY+~&mAHD)$6kv*cCHZcY7d_b+nR>f>;%bNacJ5+71)HthR+mXNmtr(zOCqc% z3xB?-H$VpB^!8*d)IhSBvHoiSuEq&oKiZip{=HYbO~a0x(%6j|I^kKH1bE|Su~sQ( z+;4xj3`K6J?wJ2EGLlnB-4F6=yJ4u@d$mHs(?9uTZo+}Os@&aoemiNSL0(h1T{2!o z%Q*_xL;2Dze){BCe_BF$;}49AG|d@Jsck9sR{5FJb0S*g?I93d8F(Gs;${Umtd;}< zoTKYJFS+K8KsX)M&tE_Ax;B7<{k`DrF{`YigWaQ}=3+WkBEwb4K_2w%f}wOnNU3zu zx5tRtP0?Ja67ap9d$nD~mgQ7QR02Zeb$0oa^CzI;Gs}M|vGhqD1Rz7`ORy3?BeGv} zWUgnVFPGf6dGSmve2){+g^>|3jDtDQc3l^&%f`}FP`s#1A*cFOoliKjMOVikBPT@Y zz$I-rviTkSFjTW={5VBmm?7%)V_<1WL&sQ`uwX*2bAYZg^5XJd_1ga2B$Ll||}+Sb?%PV9}Mbw@#_BXA-@{esffB9LIM zo7vOVejIN0G5uBQw0P{CCVI%+#yY_p<4FluoqVvsHqNBZ4a349NcKCpphAkum0~d4 z(v@Z}VCJqGw6*3=q?x#JvdO4-Z|Qmz*4SccXr`$ar=clSWJvm^ z9`^}D-9HY^o4ixg!`^LQ+g08a zNF@D`#5iQ?Mj3pZfyJVjd`ZXWTU-CM7%d<4>ze%FwGBzZ6 z`rV2#+bE~#wMGv*=+I2GHD0#%ygW9)zs9&NXZC=LtB_P#hMGQ{xyKw1fE4XbtOy>0 z2m$VT*YXIxiS|c(oR$@DdATHgd6sgu zz13}?a;2eLrhJfT4p>_WN`@P#1_(RbsyMZEthl*4&5GQ}sK$kM!{|Q)t54)0U=4V1 z#s(s0v-KeTe{mGwMcoW4PJa@QMXOx(Dnsj7+)jBq#P3B>Ps00DHeD@vy3iaSIoj`= z_lm#(`5sOr*VqamDUH-CAk$1(9Ix*rqo54e5po zy0P*~th!IJ#N(qXaQM`Bl}be$d&L47t>I7{Bd!}Lk!vnX6{plc zjWBT2(h5(!l-?#2_NH+S|G}oDR3;4^97W|+ju-SQ38kkn>{VnoAVf~>LSx*a0C@QC z@O^@_eiMq7Qxj$vt@rW@$*e{#y$IH{^19T4oE>=M9=%E(9<|$Q&x>;nO8mEr3>z)4 zsO3NNc$)xYJOFYERY_FAtPK5&YY(-&`t%$_Dz^a2=Txwk!1A$bpP~l(NVAEcPzOh+ zaqTB;)yE0v8LqLdB0O3nRN4at9HU8kU%yZTzrx6lKq;uP2*_qbmjpe?>daz3&S(~A!#?sJv$zNGRE&MXY=2N~A z=IOxAfhSm2@}Nmw1kNo5-fjwqcj;oEa6|3zu#Ft zQ0fgV08AqpUIe|c&4bt&*Jp=K`W(nH;vL%XZkZ%3ANN z{>>~ggT_(!Tjo;BmKI_i#&YMHEp$kUWs~R@mK8$wN107-86(aFm&lGp)z74N?UL`D zOd`aT<7C3_c_^MOZ>=lTE8i8b-s@>4G3l?+ zfATYWCz8F7EC~+Uw)vEtsBSq>(4h=qkeS85A*BVXs4q=EDXsKp(KDLTzLTpM*QaYf z8ECb$EVoz0Lbj9<#7*L;kS;sw{u}z{_sVMpV$ljI^{NF!`Pc>EXJOl+hx;cQkp*k+ zL~8C~QM71d6j`43{x^#tk4U~g#JtQS=B)EyKz+Hs@@T0+dTWQ-4;H56n(FfA8MOL{+^Uydzl`__EOtzzS?sNJ)#o$(v9|pGuXV76T|KpLXIP zuo-_c#dBamTOEqkf(`vW5$RAG&qZG?hQ9X=cvTv{s8TuU?VdbdyS4|dWgs{rpcwU9 z8$SI}Mrj^zSFycG@rXefZhtEGz05M7{Iqz7x`5wwRujMrkcCxT{C6$Dne}bl-b*Hd z|6EPp0}-8}mu&nCUSyR2TP+boj$dqBzgK(vTIgRc)?J1NP3<@h)#=izFILWFJEU>P z@F^qLiI1%&9N*C~_H?F+3%TH|)G#*MnR&O}RV_{scx9sL!(9-EmY@}S@J&ffiwvZ3 zGu(Z%O^arTHjSl!oO0%7CyAQz^EWj`q3$C&lnRJUObjwPere~IDZ4tZVn51uFJi-;N4b-qkdMOUT{WzEWqx;Id@c+i@q=B|g`(`e31*Un=6)VB0N zoYF`^l0h@^I0CLs6fZ4tXW}I``q%eu9T(_m#`#89(<_^57$_*k+Q_~Wjju%%)_Fe> z0Y^&BZbrZ+v7s}ye_3mI#s+A~6Iv5+27HuDAB&?7hW$14vF1S1Rig~dIP!E8C|2P9 zdwE?r<#_;bkCd_6R8aL}x&zRPV;S+~XE;$D9mGd+4b?NS4mJ)rx+}2 z`J@=yb*LDY!Cs~6wos>+w`!%-+8Td~=`h~0gD+H~6pi?|v#+}Ovq75w6Gy>{D*En@ z;Ceo{>Ij3{!Z#YVfvB^8(j7QbRuyBFblLoPTN?>*qF-00{=@G?d@e7I!B|opQcNk& zi{H};zcHG95tM5+3y6E|vtHKyT?p;Edv%iZ#a5&bOPDD*jh`P>5H(N>Dd#*8!l%=? z*<5LAA#12BTSoHaS3dhUhKeR}9zSL1dhVfhmg76?hklU_PKpba0o5-j+jt20h>e+z zbNNm&(Ao_IWoe^_7gU{+u@*7U)ne-qvwJ_a-u8cSTMlaJufN2ZZOY{tZ>G1GdVpo&Z!G&zEQgU6Z14}S+HxA(6^L4|ozhG;!Wfj^E=xGl7A3KkCtc>(s61x4C_Ila6VqI&gi7%w{ z(rMzXBM%Q}-=m~>E$;n=9&ac?I6YCaq%b7jAUBGie|T$)BI6417;a=n4)X9r;=s5Z zTtl}u{bbjX<wk3XO8`eM+T0x#bcQcInvDE!yIcFmMP~dOHC(6H(eNUoD z<|g!IH4az&SdqG7!L&TI{?74J=~gjz8k`;acITrk#4dtbpZDDxjk`|Ix$;aa$3+QW zs8zllQV{==>%W7zb`57g}a3rwa z=ORi}Z%1!<>_v1%_yw`=Kwy33ac=Ndi=~90)<}Kw!@+5`YX7XpC#r?d!pn~KS?cdt zrhHj|9C#=Kygc`UJ67Wx9JdJunczfVCRT_9ucUWB>w6`6F)Vt@N>rg^wuIZQq=u|Q z8<>t#1KDBIgsRd#M0H4 zz5d&1md>;Hw}&&yjqC3iA+k>q(LT{oq3}Ze4@Eq0t2YpSoVtFB-Dy9&Z&tG~o(Z^HePIsfaqI>EXHPA_{;Gi8U^?zChrd8ZSpgJLtA|E zb;ls!b91zN%K(F8+%XFg;orR1v?snNekgCLSWmV4Ng?IcECrOp9%`Dme~-Zx*!{A7 z%Hb;2lWk`65LDdL7bT3Wg>w;}^3tN@YDZtVZZu#(`H2Y8@#PD5(R)T;ic{fXMI`Ua z(G*$L!Thy48@+KBO_K-X;?WC>>ci`o3Kj4nZ~6Ku8F-RKoF79O(8fTZA#tPLV5sUl z{yj_IxmoltS`OC^b^H(DO0iXAWHe1laDO$7Cd}hPP*uPlD?mleWrDP-9kbKya2I>=18l_v z84{g1<8Cus0GBFRysN%~kSV98>4S`;^u9-lAKNfvrZz)29g*oY4hBDj$G^w9g)!gs z#@!%xG(-*wm3@h6I@JqDe=2|Cw*CHMEM+(s`ml(#FKhv)Bi@7iMv?=vPas zt>pE+J^$aQEkyDo2G8-*ON%Q*kYP?rsQ(0r)(q{fX=fvlF^!d>npD`3fDD_{y|aeJ zyE1cLCa%>Z165fj;>JvYqF_AvNsp#XlFX>6HB`u%)>I#l`U6tIUSbU}V9Gq-8B->! zTzk#=2TOYR+Q^RK=;8Q$U&UUX-Jp69alK!!`sPwb5usP-6lAEW; z^EIq?@n8l9fpp_swUsDp77T&w%=h|+uLuCR-IHZrV-~xhzxFW{~i507JJpL^))L)Sm-j;Qc6yL zU;9F*oyf|X*rUxc@IqikK6@A^NRp2MGw32)YJj?WEJ z4cxnmyDXRY1JxFr%0x4&O8cy$twpCaE0)#_p(bC(&P$dRuguD>>n!={I%4VM5=mHd zw<>R{eUv{+(`W3i$o|g#q)XH4@s_a425HD$V@!~8Hqm->XM?2!a%}Tx^(i(Z;|Kr5 z7WEyXrJ>(nU)OylOv_wxTX0(NMymMv-)UwP$^Nj>>l2JQ#F}~(VOXnqZCE`2e3&g+ z*P6gQ8Lcri{6BbWaH!ncy(h6g`~}y&eKj+5C5-FYmBPi;6dy*46yI#|l2%Wa2`ega zZm2-<-I&FIvN@aM-E{WH?aTuvhn6--gq1R}r_RsI_vXz=flrd%t7@!<*9s$b9bxbu zhJ)+rQ{+mqrv7-;gW49@7oNuFn2mm^oi4iel7;#70dtCIwt~@Q;rV!I!!7l7?I`hG zn(d@pVF*Q@LVa6;ZtID?*ou3J>{VbdU2C*a5GrF$D`HqfHTiprOkcij+obiR9{;SX z-||ki-WI4e<79ll!=4m}2%p-2X&@oxEp*OK(we_-PyN>^}cFyENntlK2sx z`97L~F{hkWCL20!V60RrVBW~LyYwu=Emgpd_R$-km)%0&1F=~Y8=@f@xjW-%55RY! zw<;;A&AZbBfFykK0Tx;VA)PB`EBQ8@Ss66XH?BU%dBl zYaun^pI6c5ZFy>Z;HZwJeWlc3!<1iR75L*fxOhK%m-bLobRXf&q;C}#vBszZP*kq1 zG|0~N!V~anpmk{Qaabd$g!(Lq$jn3&?|C9CXr zHpA$R#4CGd`wJ+@+M;^Kr#Mr6JYvivxhiG0VnSMe!eW>8k5i1Xv00?xiUw-V_lNrZ z@ZDOi`0R?zow)uIsnbKI^W}5u11aW>x1|s3+9yL45Qj?&ag1314F?XwXkW?%R_(gE$v>j$irnzgPLgVD|L(>qYIbT+UzJ&ox}AEFppq9* z?Mzf-9>W#4IRAwqYh(x+{A(8;@ErY)Y==C2ZEa3Dd7xxUA*F2=VN<4)aFjRt;>{I0Ya>>QSL#Fe8m4Am@0lzj3Bv()-BWgz! zRw6X=;4AXA7@q1RN|&G-P=RYq*K4HqI|W*&j9c~B=F)9XHK-@BSa~Qs`oW8Y;53NH zF3e7*nHpfB!)`kLLYyJ;I%<*yL@4pATsY1m9IpRl<~7qg@|{h}!@9#N)FT5pd+lx6 zI-xRgGZbNx_0^{QUz&R%%@-_Kva+ETI0Yk)ZWa%$MaJT>OzDk?AbhP(#Ii+ zBpC{oWsjX@lJQM>>ia}FTgl-4?>$+3=ZwhqhYGkA6bSXJ-mXGAS&j!IvPNhi^A?@1 z^nO=!Jep7M&0^yP7+H#1u`mJ*o-jmJk}ch}3w!z1C%o5^IJa8`w%CAb?o zb#&FwnMT@@i1NKKx6p~gP&Q+&7sh_y`4QU^4kB$dJ@KxJQ^K89m?md=4K;HwL{v=z zW7q7P;H}qnF3B=I%qThOR9rIoNr1I;D{1gi8qwN)XY~8WftG*`uash;?*hh%INqcbJ3H+ zLZH?}NuRF6@(%w1CJi_pwnyozZbgIQ*FXoL;RmOc*vV)U$dm9F0%Yva=gVn3eGE8E z7!Fi%>q_+UUT;}4E!yv-AOV@H@dixs$6PlFqnS9uH2v$3$mSU*m77z0__z}?9Yh1) zzmtYF)T9tuZPy3dKt>Vebi-tL#=o2ML^U*|*py+`i@JpUvTxyBGm4AdbkvUNtyH>S zP2F@?C!`nZ)H*>JJyQf6Fq&4zx zAL_!BGpsbcWWLKwIbg`SSh2ArZe<&q@4aClCO({MbCXN_R*XZ>BC=hIe@bRBqlxn| z^v|?RC9lAE#*fHwsTI_az#c_|p{`=Mr}7T}OfPBfWpG)s~QW|4lx{dx-Hy44f3HIf%GPTCo_A`HFfkcyl^ zQ0Qbt<#q0_VTCKZo?4$5oHkLmJ9;F^+(?PZC3TS_DI)SY{e8&Mb-MYu&MLbO@2`gl z`&wX%O)LFmJyexW)=`NuTlv_{Qc@mPL6%VCe-{H27VH9W_DHZHbUQ_JMKE$P)kPm? zBtF68>VT5=F_;P|6H|f@SX7YBFm$s6aYd2sKlM<#J=_hYiJ~puWgJI+bZfE~@w{qA zztN!H(Uk-sx~f}>uVq&ZPe`sv_HfTy?oiek!SXI2n$4Zl3AJ#C7###42g^7YWs-Mu z_vid4CX7p_MEDuQ3K`8!_#0I1pb=SETyFsxL$dsbj;8Ye7gF^h7Gc0S`*2Ibf{Nh0 z%tS;$PG1>qtm23`p3qL2`&lP(wY4D(ZN0##9}}W@)cI8N7>E*3>9!2=uZkc#k#e_> zLD{%sMYk@^hAAK z#LeB&z_ruMaBk)CVpZq{m z$jgetLkFskrWlZBV`w?l@p_KQ(Ji5N@6B^PKF^>Rxx0&{B9EOmV2su*3ejYJ3-AAwiq_O{7jYIbbP6O*xvNh_ zhpo-smg~@HBxWmT_?0{bYuRK7H2zm@u4DUquHVk};u;H3HoDir?qAW_q-)d3|8E41 z_V>SQFO5rwKBWbWk!Xy!=Q6#WA9Q#CE9|;7s#j6eYCRgzagWwi!NCaTmK8LH5Rs1sO6U`J6xGHDM-J2gc7!IPG4 z`?mh}YNzpKuw=T&VU3#afO@DCk_u@;K% zKZ?-(Tl6p9_*c3A-Zbj}e^n?*lc+-f{k5p0ljQA*`t*iz#Cb94YLf)~5%`n?Z_{D& z5!T=>HsjxFPE#6krz?)*0J9II?b8l`BuPbmwj_RQ*WVIsJQ$lW4AJWu&=(l%05)N^ z8qw>U3ypF6wp$_^Ez_>NYQOZQS6yjc;H`H!{_yhwRk=H^5t?%WllY07vpG$;t-jHN zY4r(O2Cq67CvyGPrN^De+71BMuj3*DH_s=vZqVMuHQxZkZ*`X`+~Cxmj2K3TSUCoy z?s5sXB8@e}|#c~I^h z0pRzww1&2%MoIZd{xRO2A=pCfSD>t6?5F+wp87a(Q1r$d5f|zUz28-h{51i|v%L2i ziT;jol|dJ+ZEwT==eHMrzg`h(JJ-)nhg5GX;}2J{t$-o0MFfq7D23Y)qGhjRfyeu7@ljIe_b0a*~ZRwBByiAS0mcM;L5LW&uiNRz%ZoX?ZN1o7cRC=|88S zv5nn2V0%b`2Yx%d%^>pjLq8tTrC}PMkR9@d{bnH?gU^wr+OEsh4e({7&DlID9J`K; zRm$y#_At>Jfm+*?9q%Q1V`s(@*IQ;SZ(1!`^QpY_z;O`4Z{BdgDyJg&RBRv2FI3db@A z%?>Av5sN~bbc%^kko%J%U{`jQLd}H{G zu#P7ZiZmn7lbV8`x-*U#@z_8u)`Kazc8X9B#Ii6yULJU2|T1teUaAb36C z;d2aAkMfHLJoTRK%If?Y)9%XiyFv!Ec&GKe3jtlp3yrkYCr8n+hvV(p%cFwD@4NXT` z0G-hS;{0V-m2bRXyYtVUJXyjv$Cv|su!w65&E4I;Su>*Idg|2d7`t6>gd0?NGbLvpa<_b5q4ZJ2)L_KdtvjxZB~Kqn~ezZ z1%{ET{DR~G3W@U+*eUhNW`An|tkZoXffnB3`p6l(b9vxSKhQ9EyEQqg4tSIeLPJX~ zJ5iuFJ;;82x50bI1^i@L=&;E$(SD2Ty}f>7Q%somo21^*^=*jzaes>2qv9DkvWLd~ z=nQz!_%JWmG9BCPhgC!OzU%AWE3n_s|%>rCSq0O@bV zVJZzI$E`u1CR&62fZf~^#9Nbtyr{Y$IPm>4c%Peufw;9W|ByfmG>LfY$aSg_1sYxe zk$_JQ2yF!Vu9AIwA#B^uLBRgC`cZ*~5prES5k=_f=FCdDU*Lj&cnJe`0cWow9d~vi zJg@iKZBKr0VO0W7S>Nz|puayI3Ay>ZrB}Y`xH^!U=u=bJogPHgB(=KX$TcM; z5A4HpdW#R3EY9?O{ZOgnK06g7h99fN8pbXKnhCNABwBd=flUX?q1 zyTymvv$p{+3spA<9Rr{>J68j!{Xt&6r|ay?nQ=()6SCq5dU$*VzJd|-+)4C(Xx^uV zJcFM|K-)$E0^q)lgOLhU+t!P`m*snB@r2FpWT9ar@Jw(0M%MxO*}5LH=%@@hrvA?9JsMlFMw7mJI2=oGO^^4w@{_En#axcyOqz|)=Gb(u0Druz;yegInC z&DIL&c*U$AhugZ*;o=$pL;F1n{woyR>fJ`xR+S&)_yq7V#QQ8mu17ihfZOj;-ksPl z4t()LUy@k+4xg*ya8sWcOu_+p1AwlJUIcEgCMNHD!MpO{>zTHvkVlDBaJ_e{=J(9y)r3cxdXdH^u2zJW+b^p|-_-sTqY=7*PFnl}#W zz_-cB7mu(T7R@bIOhI5;Ls{hG1iwdVftzTwSogCP@0$(3#D;bB@!^$0$RzDVBQN5) z%p;D%$B#<2{2*)4HoNy-9ex$~0kCx<4xhXI)%S$NH>lNiLfp#*R(XnB=>RsIMag5EKde%B4aIqEpfMfqQGI4o-$q^oocRJE^P5mtYLYD1&vDWm)>~%n- zCwj%X>E>o9d69_jdDt$2i~X(ZCpNt-G(FB~`;S-UQ$x@aHqvi$(EM%=p68AHc+!3 z<`mMn6+MX7k!ZVZivv7<-=F|~nfg1$l|drmeg;dm@iZ?=iyDP%n0@`v%v*OPWm!wE zP)5MH(G~|vgAH$yLd3=RN4Kv^cTNs9#J9jVBF}8x&^BH?Exqxv1-QEBW^E4(TSU5Q zhs5{}H)PVqIbn;ml_rYtGa=QFO@4giPo6%Xw8N$-fV00zUl;jmog)_B($2zhuKJI~6y zs1}}npW7gyn_1cs0WQ+uagoP(AT-b2s{>z~x-Fh^a?#@T+K{v7CY*Ne05N(td;~hu z1G@Kl6ji6RZg&WLFVf=8`IoFR&Fv`S>n&+!>+AY>2`uoAe{SaEZ!IRdoR@Eoj0{Gc z9BmQZayu|G06j;)&~I^J5xZ9wmHEU z)k1b=&PdMi?WTvUt=rqjbXgphTi$Gce|V5j3IB<_e)H|3lUlLdvqcUdg7f5ZrZoS! zQN%4$pKp32?4D>zd}?_pENdiz zc3P-C$}{pyMi$$phz%T$DfvmboK2A3n(TnWB_43-9$Dr%Z>fPliv+}4m9d8`D{^vBQsOD7 za!?v;!f+6|XdpF+SU=KamT=$aw>t=V{ISX7RqR*Ij4sWJ7uG8IHbCk}dCSzj7C=lg zYP*z9tSILSe8a_aDKEQwatt`EAtCbEYp#&DkM_fBx%(Z?8&3tMY^tXy<67aN@)8oQ zj}v_1*+aznL(+SQz|HcuQm|TM#UwBD@{7pjY+vB>N9?nF<|M2Z0T4ThPIJ_A2vD?q zEvT*hB$fS%lZ)hz`%lU(qWZOCT z^|>SuAfO5moD(W7u~uD3QIhWCG~HN9@TL3v+RmWQz=l?^-*o;#*=lc6Lg~+*xMABG zZ}*T@eOZqiy9KqIr1P*>Brs`8K>~0B5ZvRE!J!>gUYHTDfPPyP&p}r?eGoK(w}!{P z9PL!~X7^-B)^p=+^aCXFH~RD%aRUb$UecubxX)~Dz9(BBUF&Pa-r?m{T@2A&y{~Mm zAu0g~bv59(x*gk=D9~AepdI{Q$nU)bl}nXbAf5SlW+!dR`@Kv*jY7Uw;4TA zwLhoIeDl&n&~#st+49rDQVa12m1Nn?D)i+c_V`Er=~iTP)d0f7+wq_@J+&ZL)a$(R zgtTB=hTr|_1ZT3#L4~ZESVZXdrM#a*(-hbEoGz2@{b}jz>>SB4z7u3YgnOY<;&itm zHJ95|lv{!#u0jr_jk2;+x>CfjDP3iOhfKYX|7uJ>jANNeLe07mdb!nYxS|MpdB$8> zG5jev>sk!W@)6{@y(jF@u&;LfYK2JN^IMgfGOCdMyD@x3`i{fSnU)z2kx5m5)`WlG zhU53E#?i>sZm$#Ktquer`(9?g5&tFwj&&TGkT09UfRuinQJsZ^(7LAqilXJWkFcjvZLRs(*}X?Xh_H1a@)#w|{I(>r6L2_8=0p?Q z`q3Oi2tP4LR4XB)>bPe`m2Z=rfVr4<&$6J`xUAYT(C%L8W4)C~ zbz9*Z(Y2?yraI9uELyw&74DGrn>+DJ-NYYu_J6p$53oP$GMymnESNBD&opB`9(F~8 zCc(qHYje>Y$!_%3uzTI`8l3z%=Udqx*`TP}0QlE) zzpyUslciezNW=8dYJb5G?3$9}^!#%AW`+VGQa?X|E|DAP35K`>r{*cLvi;Wltef+( zohX@*Ook(6+CPWf^}T(oNrnqYos0RrH+fFE>t(kcCAm~Se3w^H8w~=I6vsI@UXENW zx?ao(fC>Xmrettvh_%fv@WLOrZ$7ty5BUY`ys`_f*obUfl1tX&HCb#!-<|<$Y9WcA z;MWEP-K4A~t1(^X)?_ZS2lTm_$+QbR)m7TrT26{UIV12kE03o4h)h|}gxTX4oo*X; z+Y${ZeasQG_tl%xB0P8b%9%$N%h6G7s|z%T4^^HciI4CA#?1cmqK!R-1MzYh4s_04 zPtQ+eYuGM2)n>XKIwX#?6xo?ypY#8mt|m){&V(F(Y-BO0j&C|JD6+08dFnOprcBe0aat4x!@*OqDL&HD%U8_Ug7tMpRx=NZoa2Mrl1Gd(B?p>M87 z5+V5Na^~aYY-q-cg*41i8ToGwzuM*H_p&tAw5(s#fXD6#Q3IV`pu>=r54wPKei|my zxx|#%D9583vpL!OypavvoORYdIPE!ZuDQRQVL~DDkK@m+YMuLiE7k3+kwwJJ-`CR^ zGQPUpD)RkhaQI&A7Uxbf=I}=CJIzm5HrrH^e_NbsA1?t^kfW;*Aol3Isnu5!Z1ktYgqeI(`n1~Y0_isz5# z8P~8?fbDQYMrt!K&YOV7zS5-95nE`Z`kH8K-k12&A4kl_I8(#@m zX!l6(GjShVo@aD!*2Q(KhA7X&%|K39x%g~y+Z$e4@}6yjW8ep9buISL=WER*1_1@e zyh5hk6OxPF07)wEhkL}ZDCPW!3VC@`)2;Yb{vFkI)TzOh)?ns-;P3(82GqqoU%7A{ zX!5o40B>VCAgtHs#bJP=t+na0iEoxd+3vNe(b@J(2-@$stJeUT;nd!G_{#kTHyZR) zM#b3p(T)rK{R`0$+UeVTr-Ye5B!V8zCGz%tz+?L4w6W>d!mYdEcp1-gqDr>p*aiv| zsEUpgPwAJkBgqXRw@&6Tc2=`s@sxv z3-^iZzEz`*p$uQ{YZq08sfH6HQ=PQ2TQh3*tpKYJS4y8{<&9US*LF)iZ%VrbGEz@M zNQz3;UI@?{JOby`h&)tt3tz^j$Ixze;qVF0L3L3??rdZSD0$k&%>6Y+hbLhA63+{v zIo%Mx(07u7{x0IGNd@hADyl^5Xeyq*nbEd3y@qpRsm$ueQUp(!I!Tj499j`Q!&OI_JHp|PxB$Q4_MUuQr zEZRc;QF81wwsCQHe>_?C@fP<(8n+{otrkSV=|pVWTOn-;z$q0MBejQap8F=W#v9*O zBI4oP71|~J)#>Z?*>IqTJ}ZT%P~)9njTcW;uTL7sy_2Pu9AKg{LB^rz>*v0jeiX(x^_PHzRlS=^B(SVwcp8U{3zn zUK#0lORB#+TL1X__Dp1ugs^7FNX_uuLxMAwf1ihc23jA|U_mnU|Ej8gdx;GC@B>i} zlcM4BhV~b-(-|uN=O5Se0iRKC%^CXs@l&2)V{+3kpI-A$THZaW#3Ec^4a2Po^yW)J za!F%%B=tG>`eoIcs_P|p{e{32Zv0~ffjIL&Vmk!GN+urJQ4I=DMf}5)Wg{i@y{Wa5 zOE#`3EeW1?&v7dU)Jh?8R3?KJ# ztvo4wfj5SQ>1yuAOYuvu`SVHU>j>AP42F~ic?SZ)C1VYjFrO?f1)SpSfmWEeC2EnJ zzz&d{W5w5YqzP%M%2C~11Isl&P$xE2eVF>C?m9|V>2?t6(~9zB0m=Nf4eXh$$W#Q6 z;3zHE99$5kfYu)xI#P7)B9@5LzO9CC;%K`EwNga9H|wPbeP>wdv8kQSkRfu_;f7Ohhu^)V+cWNpsY#s8Oy2I@)Iu=U-xa z=gAkQr)LTsze6SKZI9$`3=ftT`&8XotOOSX?g7-l$6@nD{wmzCI9|Q z#8r(MVc>F+`(euH#;eV>M~sa~4_5p+KHa69dO{K}dOpH?+o5nxAjOr8tuLgp#(KQ0 z4ZP+%%mIY}6k1?A8`8$(%@-u2M$+_}uh|48gDmfcTusmI;pAUlFkZn~-Kx#=}=RIsWNiz3g;lUGU{EAp_|i!Q?|TOR{;nfmBG zX!QD2MWVywl_m$DZK=7>Bl~LrQDMO(Jc1b}T)MRRgvCMrvB&K*PCxi}j3 zPLH4nvS*MJXzpWuIjzA-zcbr#7tLaL5-~<(W1xUw*hA5cO;|*;EYHG2h%8c_M0H6* zQd3q^>+)^=%v1&zF3(ps^tm5i*@>=?`nSwOzp|r)_b)_RJ9Qkd$#NpmzTzi5;>S2- z#0H)4s!w>@cLCGhqs);S$c`C-xcFV`Qd9KEGW}g<77^Kd??mS%y_P!DtQ{g7n)2=!?-ylK@u;0H zv!^)F_*k2w_T`L?xkP$LUkVO#szqcH(%`q%C%%i0=}aHHj?U4s$>*$r6wt^?0!nju zPzj&(;o?Xm_iCroO^t4q(j?0{=+u^6-IlZ_m~qgCZ)%-B6S(o10_2*rr98-rpn27M zj8N|{y4e$Hyg4Ncb=@J^oq7Ot#jpk^t0e?Xr`6P56zK2Edkgq*FG&$Fc^Xqc_}Y=T zPP8+OS4LpdcIo1|Ea=L#nqk?rQP#@M_X^rTqUqxTi+4Fn=q8F&F|9vidV2x$?>o@7yV$zXC{=x1Ev-fLvSSyolQ6PkqRMG93lpF_11%?65=;yj z%B=S7D~EsV&%|fEiPU)F$I`J~$*q6+;@VYX6zoW9ViTf3h~qEfkdu(`qqoLxqTmZ1 zjE`b1xQm$v34tZ?HJou5k-^tjA*M)~I_~F9Wlp{&Y2!nd*q*mapZBA9w{rLigNSVY zh%tHt^K^UkY1cCVymdC z)OE$~JlD;k2oHQUsCU7-TDeH2B(B&@P`aN}s?62(`EWH&JHbeCzhT{w zulC-4capTSjrLcPFI!X`BF3~z_ln2PMLl{eb>^QTR7xT?{2xWkxcVQ(B7o3!<%)_b zU0s<=<)Mvg^0%ttnF2`efok(&7XFE=I}sw{M8_7&OW{a%7NR8C!+xku4Vdpr-^$3D zg5=c_w`Q#f_=e|5Tdw0i@K>R5Kd_Sk>9w6|&4$R{qtcXssc)>xE28XrsM>nGk9N&W7Ran3;copVft2q$veYnUkn8P?wl`qRH^j)O zmZb8lwlu)2F*b)aB7$cHd0A9;`u%z{KYz_~?7u2Y@%|`6OV%L}-HpZCuVAh+64zin zvt^m`_|6kx*mlWXigmE4NXf$_HuYuWr?Kgzi_KwTqNjCZ_4deKV`Hb+jDhd6O;v*k zFT<}gy9m;0`F=eextDwEdE)98E}X+FByPpDn4aNdzr^_C+ngCHQ(^Bd1wBEumWXfm z5B9-->T9e#_|^lo(Rapot;oG5^OCs<<;;eFR2n~etv|GUj_c4J?X{_C;k=wGKUQFy zu1v?h-^EZ0lg~?FDxlbhBHf1?vqDuMKs=+CGp;_9C-yR%7&7`bO?(jUwu4+cy9ioL zS9O9%nfLp7wDM?FOT;|zwj61$M`}X!?d=RVK`dlP}JAwyDmWeNj z%Vi~57`oj-z!OPpHThG=T6jKm$C`tH&_|mCnokELFl~xeZP;c&+WIeclXNi{59G{R zfsQ%-GQ(w@$BSFVtQC_#Unbj-zcYS)+o3=P8@EdD?1%DuH>=46-ja+RHiSHa4jxOJ z-AUUECw9k&4rVGu&@K1%=Er>kxB-i5M@2udCey7*vImQ|1kEvtq;i0G6#~gNb<}J- zJru=!CM@4r9=isbo*O>)23qW%>5cu=th(779MO+k*xz{hq_N;$Jk-ghklmi_rj$TzPP>yM%ytv@`-PK1k-ewB=Sjf zy=nvMUkciI?CG-{S&a65`|`C$PDM|0dk(dph~(v;LSQ~82+fcfE+^Y5u(-o)&@?$* z{47W@0YGL{M0W0ANqhT)I8;xFHP&QnZ!S$uP@B1V)HA8*{|$av;Q762}!zSImL$(LylQl4cB4HvH5zR%cz*WF-6ZuG=r;+iFtOw;0(5)Kp~bYOT5?nk zIIdlbuIHdj*g8#bjXMuN@GXV^DjOFMA%cl3f-J!F{KcEA4E#sY6uvM2OYG}zP;{5X z2rBgL@wt2mY3R#4O+uM!rQb#72c>>^$nJQYN~j6bWkqQI2$SPF{gtrnjM{iCU-yLT z$W|teLOhqH#RaWQs2KD$2P2b39VOK;fCDAH$k91@RMFYo3m7lub!*tmXwm!A4RZHy z>EnPt41dN~UgqsbE}LRI2RKQ!q4oHodGbp;+|fxSZNplsYxRn+xyzFWxRL%-3*lM1 zZLvsU5_HaP$N0S3@sAs7U+%vzes?ROvKbxY#v49Y=3bySZKmp4$(VPbsbv@ z+(?jrJhDLRXtAayXeiZTDdvV&67V>Z_OQ^>@6fqKWVUYihX>M{?WQx^JG_BY-nvaK z`S&h(Z<&aj)C@qo(Tg6=OU4^xW<~?mITI@DAnOn5MeAJ)HK<>D;xhG)CJss?*u!_f z@f+Yq{Z79?bxkz?v~pjdtwHwOP^i*aW9l|*Zii5Xv*peoCn+WLq)r2`M>K(5Wo{l! zJnDXgwKA(4|D#*?Q-@{vYZie6bw{{CCdys#iGnn^>+zY4j%YG)Ug&*=GiUI{gFnVE zt{04qhjqA%jsVBv(wX~{A5P!U7BBgSNq8l2u*Z6E9k18&t)2P=J9IFI=)*b|);jNI zDtEfi-(vv%{1bt_@g<(qJ0;AI_Gytp%mM?enN+YS*`oo>qb6!YJm=ujX}yAKe;t5B+7{02$HUH!KchA?0sDu%tGVv4s5KAqnni=eGHy+zBfCY zl5yuWW?2F#PLHhw>l7PQ6+eJV-p`)R&K^^EeP$H|ER@~uF<6?QxHVf!I6WLX80pK6 zKkwp?A>rreJm~lDG>A0#bmY^%iZRLe(OA5D;}sonUCJn9`=Npn;^!&6w}E)w=_L@P zc=lm%CB*Rji)1lPA%!1$f?o5xnLLG_W%Ano?}|}w-F)S1!SQPVn5s5I!Y)QK6Fh$q z7p^fOZIUon9vlbulG3l57p&DuP2u@2jF^!@tM4n3>?ZJKZ|gs>7h48Gd~4*{tiO@o zU^wb#=J|=F;3B zT3tzrsf&43aYiRi;pN15O9Q`vzvB|MCyeJ;qM>zVcWwE*YuC6`NI$OyV@wA7`@Ag1 z>HUKH;uMo?wDqg&=bvz4UsE`ETC;EPnEqme^JMV`a4H0!5eCF6%LPJ{h<=-YH25;? zXfv&A_gBx3V>sMKLm-1^sybnDkXhjCJKdwE5*@x9N3ByV4JfSTs1Jp8H5sbmP7=H= zopVMZbBGqZ)Hn{L&8{e8(Cf}e_!1N2>yImRJm|?|^3u|SwESP+0EhZG~m3ePnLVGDKx1wE`#Srw&)rpr8&zxvwmWX z9>t&Fm_3h+Ch;*sHnx^B1!YM+%Sp|cFRh(ucpV*T>mVfYvLk5%i!8ZSO0lVm8AZGv zYspF!^hwvLfcBWCe*Ln)@-sgc)0(Yq3*cWp4U382b8H61-?E`NAyMcNvvp7>zOZ3; zBfAeN?4PH4IF*QK^Pc!gf7h<&)@_BIbTZZs)};Tnq25^u5jxzhubfEn8KNpM8=_7= zIzj1v;+w3&r1ZuWKXX9fSCZp$Pktwt-^P$X%EuRW`fjlGUfp;6Qq1Q{s$OorIu}a? zNvQ#jlHSD_cF^2+T>&Qq%kNW(3Y=2RJxRR66JVH`zHq7~N%d*Ui`S^9`$L@6VxmQt znY;AQpMt-TY0Zqpc$GF3eqs$enJ1L{2GHmqjf3^Fdg65vKRGzCWk)>42=4tU!5LZ< zucC22Y4xrxt`3&f7zB6+{>~vkP0Re94~v18u{e~O$EL*WLlAupK{InY#7!IvqhG*qFLUv@%%0bh| zgzPL8Lt_vY@Tj7lxzR@3l@&;UCBS^z`HDOLh^8q_$F)tNcmktcR;>tepV7mOGz(at zCuogD#9mwGKIi!tD%uHt{z@G9+4a6)frq$!SwgarJwFe=i*43(L@Dt%{s3Ap%8*2s z-YqY4iY?>VV;a>dHr@Mo37_OHbc^oh43sA|_Da!!avvkkVV~cm%+w=AS4x(*LM5QP zbohl5VrntCm;l}937)R}ukf$Z*9w@EDHQ2FX%(12*!HYXcN5kyf7w|LU|BG1O5==9*x6@7 z-8S9m+yloCN&j(L55&x_uJs$IXmfhI5O6S~xfk-I+BmHcaTrvHtiD1=uI-Vk;r@N%k|36WdS9m(EVJ z_CtP2YWEK`>i18KL@9W7YuFsFr&q4~!j9^W6h=qA>au-`jsAu~C!)Kt)D)I$g~pdU zt=R^-O;(IkoLqap&|x7`(A@4NREK-RVSSbZB4SdD`kiW@7LlW=SPn&8Oii&!7h@GA zwf})(ovl`+k9Zl{>Ir954tLr@Ds^WvrhLhr#<~;79d0kz02Zq-lLf@5Zel4RO(TGG zH~Iy-8BUbQE4KhFEFnc!jkYoSignwO@iHIkel9OOO`$B0Q}pfK#(ZW(*fFf65VovJ z*bT$(Eca3ILzxHy9?G8%R0SBxx*9W4{1tf~@!S$QDV1Yu8rgS}j&>+zCazK(sX3$+ zO11P4ymJACxfUq-D#;PX`3J>G$Pe^JGlkAkSbVVpZFr87hc&uJMMcX)E{By%?mkCN ztvYWNur;J)%dvDl}`e9<9meMpW|)l2^g76ix1 zAeu_{lvo;{$(ZQDU>#WU_;6C@{rrf(wr?dWZ@)4S4(TPRm5E941GQ(p)(|;e$%*CHs4X2+WnIDT(*egW+ zjBZ3ui;q)+g0r*3qa(~1_K$gQ0l6I#^)^>J8Oqc7ntD?0>uQz~qMSjwgF2rJ**?@? zbnwxU;htXe*qjvuyhN;vc=3ymc`7>k}YOt zW@ZMdBQrg4_oxe z7Efe?C-7y;hv@Ctn#kXa`@FcSva^B!_8K&wc0ZvD0enN5C)SfojtJmi{0iam11=S` zsT6j9ozG+29>zmO+pGIpAC4bLh4SY#wGO1Pa^9R{gQt1S|K0$FAk+7}1?YF{PIXt} z;RDEEGs}Q(>sdY>&k&-uUv!+KA5NP9Zw}5S=5!7)tLb4K5=Ate;B?hj5fTLY(wiiv zLUTfIl4t@E$KyN=DNeNPox<8>hr2a16i2G2J6!%#wjvo@3APRH%mx;a2GBQ;4Y~kI zNs~jY2|c-2sBy1zjhGY4h?AQ+dHDruF)pxeQn+jt8dKq6lr1;?T%%6KLgJg>i&U#$ zO7i+_Ew2y@ZR&1o#POmCEo3@z+%8n%#aaw2_dT5n@5eucWGXp_+d~4^9ZX!IYm0ve zE8msQTN!fYaILvRS=kxR&?F{&H47J5PI&HVUF}x;!!lKy-sLz@H~Yg_mqoT=>BMP&~DGo$o3O2DH-I8Usv3d|)`CT_F`mbnYlX{J?fk6H%|2P%f%sQS##9xibx$5fv zJYrOdMc57Au0Oret5jOi6r7j|nW4FKzcMVd?>yq)q4y0Xwi!~#N;`;a*T1o*AD_O} z5MJPUc;-nia8c-hn^VtSxl(m3=LN;|-VS1Nh1d+W(qR{U4j>X|09MDUA=1tnh$6Q; z1*zwR;BY2){8%K3uPgni;j(qpfUm3%|9pd~k+oCnY_J;4><#xOT``syCT8MLQ^b_( zfvU~RZhRoYaDs*G=3NdYWHW+}>jn>GUL$%PV$6Rr2!}MIsKy>g@7^$=OM$D@w(t#Q zm_2K+uYeDyz+uY`(dz6P$G?8x=fsO(nalv_=)dX6Kn>F*`lGOf^b}$Atp4~+BS+?D z1|P>iZt^JRxQ_p8TcJxzWCoY6K0~x=-{ktsWg7=V=dD$r|ooF^(92P;KWkenI%c zeORm55$RE5R^UU()*kj!fTEWJ6Lm=7lxiByq@fB#BI$&m2I;%Pg>I0&jmY8PT=E}( zG5Pue@q`ICpKz&I1Vb)s3WJG39lP9C0Mq0d(WIKgn|lG3#Bgf7Vp22`u6sd}lZ89l zT^Fb0NTH3|;oGdz>IiTfnXP{c33vMkD+xQ=5*sBsWHerac+!RrzETYsl)GcBf#OXH z-GzY7Z+dDobtR@0q_Dl8^eLi4XrQ=nzs41O9&Yc9I4)ri+6Cy_hBK$HOlS|wgIan} zrIo&kM|<a*%?_rAeN0*8y zi|3BF2vmJ&oDd^!gZp6%NFcyW#D=CQ*iEPBUtTr`KaHXd$+F##Vtbe}C)~sM0E56J zU0C*Q3mthLo(WgBEZ}!&rDZTEH>Y@ugxe9R3)C#nZ+=+=xEQ+!Gv!Ju{;VXb@~h)E z7~1SD>v?7kagCfAgdlqGZ?rD-&Y>j zLj-siM17w~(b<2*3kwv{W$8=kLDK1;1LzBW;$&xz*5mR1JF|VhGXia5k2d*gI|V0B zTp{ox6;O634b}V--~KKak2c|mglMMnwO@OVu+&W6hs)FV$E(L&a}j!k5m~!5(?_7q zg_ep_KWeKNaN_qnb5N+mX6ld5`G(Y<%CNPqOGV1~01p0-TgIk%{k)%Pk&P!fGV=Dk zb)htJ^=b3t@Is0(H=G8sG9ENPyi;M2lpHlKF)|&fk1Y?2w8A!3#cEJ@BdHTt;vnPr z2g1Iben-mnQ*PDJ@U*KBpIezR^VzeXXz+{5>lM5I3HZL&+upQnaJDek;75O=gDdZ9 z6O9=`x`~>B{QJ2$I)Ty@op2gruvKC}YDj%o056f;uZAB*2mPacT%i~wDPH+wmQ=hf zV5Dn9>UnEOUw25kqbx4-XEAt{EKM~;m*WiSvmvjm_TSud_KE_bx<9eKHtumqH771= zVyYE8PwpSiW$fGHOG2ji9XKZaEV%9ka)!YDbpe%vF`M_)q0a^G&`G}6*H#NVZ~7eV{Yw_H!1!G`itY0~c`T#T`?PMH?I48yC%7_a+TP0&x) zeMO`toxu`k%A46h;`_YM5+Lx|@9r`?Xz-U(dH{?8bEvBVfed)yU zD_SbvbB`uk?ioawbt!dzsseg}-*NaUU@qM1pG@l*^Fn00n)7OO#OKFW(#Do{9K52# z@=FGUpSorCVooOE!K>Ci4U@^+brwPx*s~?|vU-8ONE>#ci=~Ms7#VULt@9H2mu zDciV2`TfEE@A8oF$T64|omxcQFLp=!`6@2aaNWadDGz@N#BL^ z#L)q5xs|nh(t<2CPz!Z@hrv*1OI_IQtF9XzWj9Z5L5)52R!ZN`X@?N^sGV{UOL_rI z7P$EQtO^{<#8}Mj@m!rSReHi+rV9ZeZVmKk}YwcFZ*6vRyU%jY04DWU>N4hkn``it){uCh{E4}zlhBV03I(>eX3Q_jXO(30xX$gChduK1+FPQUqG6Z zo;Y{z^u|-JjCHkV@p|`vIz0A}^g)>~XtWKq=WN$4>K@M_LwxUNy1=?4OgELwCzUn# z+@{QdZRm*UIMHgme$?rd7QR2bhu&##n?Bh$YSgmp)5*`oJ5}886>f#0vt9o1k@Q;k zz%|-v?~SKtbR8#v4;;HfyUgCDs{8Df#Y55MInW_N>dIUh$NLlNf@kdk=l{(gtlp5H zbHj*+=Zh75M{KjAt!*?W8P67X(BXu;?7fy)l=eklfUo%t&mnwem{`*-x_a4vS=@f{ zYN7Yn&Qw62(&Y>ZmSDiFRmwhtDfSBOJ>zo#X2yc%I(NH$yM#uRc{<9nl$_ zkC(S8R={MiwzC$cN6oTZW3Wio9$D2KYmi?}i+ZSDRBn&Zk5cF{&e(H%xFVk+5-jq} z*OXtd5XWf!JrL#?3D6&m|IAYDQ3by;T4KiOxufS7s3Bp*U0-ezuiyWiFW+K{exJWbF;4axGH>jIU(-9P`<6TXdY#}oxg}TD&@U5p;W0BYDy~N6b<}olE zZIPt|pA0|2Xizd~C7`}*y|C2k!gQO#E*|CnXb3WmaQ-@fXMP+O!kqg*jluv-$W|2k zLV`~RkJ+vSDB_k^lTyCq3QnK$7$ajMcBZmMJc`{X-=`UIwjS=5&HHL`0ZzB6NL5YG z1^J5*i@xU{10#O`1^l4_WvR`PHFxEd-#>u9O-i= zNfCum`RoT4057rS(&b7KBXds8koCp0Dv8bpX+G>m1ySl=d8B4c-(x@0loGGvA0HCd zxwB_m%KnG#=+G_!wP47+!f+!vpZ?WIpC#${TuP&pL2_36L*SI&2>o5>w0|VAGUx4( z=qAWnxO1MN<3PR!R=LgXmvmzLFOiXZVUVy}qAJMd&5iD8e&$s$${mBBq3aI=$xj&) z3$m%isKr^q4mwf?Lh>NDfiEI?u>S2%uyB-qOO&B8s%>qj;CJnqcCmblVkF;2Il{V5 z?(Y-i-BBqm_83dgjKw~7i_;Gd&qeg_JFR4R=7W|~$#Ml<>4ix63C>Ly=Kqj6tf$1X z@NsoH?C*pwQU9Jfr=Ko_!hcvbJk2LCOOzcIh7> zo2-7OdhD-zWn&iU_13Tc%-*ANok<2_{x{s{_#`pPeG6|scAjTQ)dZVa5{$I3p>B0& z`|htN=NeM!r{{Z#3@uFO?}|WHFM7weJ==!w&!je$u(AIK;$3xD*_`evm$HV>yGbHr z&tV#){{ASW``vlmu(kK|dTP)bB|#G(^gigwpyBZZ{UG?v^jG)|m=qr6d%cYeBWB(h zMP|#>&=yx)CRE9)o~&YMd+dx?t#MDx@MLak)H}byyJ2OFf#ga8+hnuh)Gcq(vZm8qs5Rv%daZ@K7*ES1nZjBMs z1$%4gZWuffOaeWS#?cXQ=XI}Gvl`bh12_JjqeZTT{_WlSQax)nAC1h+GkbHqZSMiJ zI2)XJ`ei|pgcWI@{j@$E-8(Cpg9YrQIUbpooXEwxVKTS7wsaZyG}rzuIrU~16W;@N zE<_-NT=U|dH)ZTL@S}|V2{6sIvM7rFjbG9IB<+SdaCl4RjG2|SbSJE#&yfAxAoqDZ zC>b=vg}D@n^%JJB0f_$on!s{D(H+mvJKv?;pSoVZvvP`FdlMNSG1e$^957%Nm&<0# zVK$S2TJKSLYF;zF^;;7c6R;Ben;(MfIj6b>Bs!4uR;C(R7Aj&IEs?V=vtw7oB8(QJ z6Ai`VCrbg2LcD+{t9YJ;U??%%y#yxuDlmEbOzf5sH)x6JE8#L*B~|@ZLeEq^!9P0p z87KAo=#~Pef&mRf(4qyk0vnJ`Z14k&9dQxljio|ZCL(Wb?+&V|-cB1ZHey4u=%#V?Vd`>BRCq4 z=4)zSn$6B{x~x6@C-2&}v*l9LtMR`0rz5_9_Y>MR$N?oH+DW~jV3RfpZV%YfeKd5- zGEpqQb2#M5aFq_Xw}(w^tT8mb;eXm-!^K0QU6=X0I#D;q_M|zdHdPbrzgz$qD8UyT z_ic{9sZ3Fwn-!W&=dRs4Y5&lBJ&0n4{Q$DFNhA3bHPPlQU^I~Wa)zU@qQPx~^h_1Lq06a+=V2Sgg9 z73$sNA!r{ghr?cJePZ1~rwaa&ATWcw>R}~Je!TP!pCaPR#zo)tR9S*B_le<8m~Y*S~I58tE2<#AHmUkuk6kz zbq+M>#M?4ua}GRm+~M~nh{Jc!Xw3xF_O&?+;hgtl7l)Cr9%v~op9wX{ZOsW4)V3E~ z`TdS!Yl?pKTu+><(C_Hrjs&ZYHqcol1m~Go7Cm;o#-^$UV*}VDi-e93x1x`6eMaKr zxn(~2lg!khtzHcvLhQ39#Qw6LImmRlnWamL} zYS7eM7;0=mb@yte_7QH z3=oj0=j8+TKn1A1Xdgf1_;i{*vYr=b*=^;4D&a@G*LI{5PuNOv79sT7=_D(z_X7$^ z0fuUCehjzbnJyPJ@B;gFd0MQZT%D{J6u=L#axdKTpAf|wQVddC@b`%_1aQH&9c-T6 z2XW2BlvN5dec{d*nYER?jgUc6pV zpxg>!Hg@T<_kNx4qr0F)2QiP95%zIhSYtTbLGNqFqlZ6YahH`VA-jcOb+qi`EOSWs zaz~!0rGzFVj$gzGj`!c5B{q;Q+G^t zf)#$6Uw02=ly8AW`(Mk>Z7P|~sy&Huz_DNq^(hGn#{y#Lkx)>E04SKITnZ>AR6oLh z{16p>qH0i3gU8UKDuUE%7a#8G5nL0Yx6BZ-RotGwKai9_KJI?rO2{|>;1*+un8}*V zYSKQt684R9-`~o3g*-2FH(y6*yMsk0S-g3$OTF}qR?!-2V4p9{_!b=uGY39OMTQ@Q?NAyuO*GOX=lZy>zh2E$xe!b zVzt(Te?lZ0-ZNGc8c9aETmWJF$f=GCyraT*d!wx(>d%^QYvTC&4LeVD= zS}8@8!JSJDrY*Va>m!QPix~xy4s&pf$yc;nU0}p3>`2^DF$lI_yNC*f{KGA*s%s^O4ExA0qsk;;2#o*^Tn1B{IQRw0FwIlMg zGejP5rXodbB5d$+y&|{O%H-gW=XAoMLMlFIj&&RS;goQW^7U%n6QqPXA**W|tV`q%K~53G`k&uX{h; z7ui&ZABjk`%G#KPNRbKX2Dj|M>X9;Z*E8uU&6@BhdhlYUZM024@os3Y9OLbf3PJtC zx4AX2*(>F`2BUPpt zn@G^BpN^b1VPspZ9(FLMGpv21lO>LzVANVE5^hyxYB!RIr53hxj1-PsmY8c{B%*|D zf9)>DFqgAge6=V0WY>AYuj?U~sady6A$;dTz&aWeU?rkXEtiG7;Lvpp@`{3 z1)k;0@B}e)h~tL#_~YJ`&IBDp2?UWGU_XVJ`kvGdIgo6Kw22d!RJ)^yC%DKY;VZZ3 z@KGY`B_5QZ>_u-T!OqB>X6in}XK-x3E#)Sj_r}J7E_@%U1vH6L()f5?@RSoSWzJTU zowohu8=*9Qelhd+hCg{-C!>lt&1Y}=ycM2x|NN1AI8#gCd46L$%!sh)-LmDtL-zhN zxB5Aj{A)6eOhGw}ey6M7jXBKL|AGXZ%VQ&gVuWJmEH0i7z5~kd5|^tK?YPAKFe@!D z%^s?n{M72)*;yNDX5YQeQ<^4$M?mgzYy`IMuT}w}{DQR6apNVKng0=;!M1(3?6Geq z;g&mei|J}hX3dewxB7giYiv)D5_hws5rF!?r+k2H#6FlIh%g(DSjvy=2t@M%!5w~k z>Dh7{ZTDn}QoZ@w5@9f;zz17D6)KA!9lTk8Bk|7W9{K4jK{QumR&TqdT_N0&sj|3u zzitO#{LmJ{9giiSKYi=YP!|%o(3W+XyabaBF~)@mRKgxRBpi-^m^UjF`oN>xun3$p zNgqA9oa7n;$B$jhN9w!*!j(DvVioU4=&03sYCeC4F%!5u52@s$*yw8cv32pC58f(y zoDh3<<+hc>s|m{w#}%a{_bgm^^s2zARM(=seUw+dxiO0zHKlNWER`oT`r@G%Z%qS{ z&6)C^T!}pQzB?1=0B%(%&m`eYp3rSIl%5r{LHfw;0PP9sTj>DihC2SzQHx{;-MWN@O?^o@S12PXCpM+kv?y!ht#d){E)2x*HQ6nr4auP0a^> z?9a7z`kMWH3I1pT(VROCq9>sbU*c+ilMgE!m%j4NW1Y!W(|ca*RlX|{V=G-71~{@2 z!?!!W@~&nL1#R}%xZ6W?&QII6zvrn1X#;uJOTN?YJ#eRwhc+40wAo5TCt|c`Lp}lz z$u|RQmy&hu-Hpk@H2yRbMqXo^~C3R6SI z2RzBpd^0-rYE$&3GI$2kLk=fLHGWow->NM6ZB%ubvz%FOllAePPtwcsbYz8Z8^L&_ zY~ZY1sv)`xmbdy>7{yzXGDFf4s2Enf)celxA||lSnM~}r%AWRjyp@Hk2Mzhs(=OR` zI1DpXz_n$uBfXt2!oatCFt!t{0s7lMdd%qx)7zq&nEC7q6C6dy z-i))av+0S9W$|9*n4Ipx6IW@0aR}_ziU5Z+_V@hE_wUDGmuJ5j$Y~d-RKEvXqxdIwY*Je?D~Wki57aaBP?}0bT_l@ejQer>BcTzUrWXsi|duf z@megdM>QfCo#XP_YTyvMxGI|5^3C8avOHDJG8_scjgQ%~_?1g)9bdgC z1wd57=Sy|BBS|(d_k7fxQ!S*XnT4k(R8%x+m){^&RSCkmr{cWeE;Frkv^$bNh~@Ha zDgBduaV5vp0A+FAImGTHk4a_QXHv(j^8C$hgFio>qi1((Rs$Dt9(O=Rq5MPTkUPfK+j%(;yLa-tmx2K*% zU@mY})};#Y2a>$YiZn_$ z%-6Bq3$yC^>?q5bUIb&8fbrgYMUp@-FJ{%!@fiRCv@D&?JaKUHx7D=S33nT{&0-?7Rnu{>KJ zj|%DZ1NTWCFC8)Qq8(8TL8Dgd8n{X2dCv&MWsRZiST?r{i!=99BXN4oAQ%VT&c^w= zi}}6#t*#9p*!p~$K(D!;59SsH;`*If4?n;C71gY$}{HZnt3PfzI# z+&iZfPw!}i z-#`BOcAZ{z%2f+J{p1z&juxmP_>4TY-ceni?cq&bs4MNpaI2GOdvPQ-oBonFqTgp> zAC`}V17{(~tk^2k9#U6L++2KEhfonj4&lzL^cd*&%DLm*ryZ6WKgP*)& zDq_scG5fhg7^_t0R$?vm5QO+d$0$D@h^m4ilJ{KCM%&QV_%=UtZib^Jg?)YS;=@6H z=#^DI%=8nl&S~JbqAmGi6stMl3#dbN*N~U$hMnD+R`;)i=s6+zxHDI-f$0ACMzq0? z?JvAWOW$OtKRu3A#T-X?N>Ptk98=XGjl-J%s9VyBR$xxC^Y=VGyT5fjPZ0HhO>R!) z0zF~o>ozJ5G3Op{nokY(pQeJ7e?5%t|H|Q$n`wskAkZ6x2hXTASbqYT&Z zviiMo+t3-mR$@l3wx@D#ZB15_Xvdny2BEm`ea*(EY#53KAl>76hok3Woi^6tw_cTm zx2R1nUS}wHwd^rq{E<@l#OYfUqt@yp-%K-Ju`dZEU1hAWS9Kc2neRe;L#5OjCmHy$#gmnrl<>+~8aA_c@b3 z3?#BO?%iO&%zHC_&q$Q}1~xlg)B(`s?i>#7t&p`p-AFWg@;y#*iLqMe&7I<|o7se; zK~JOf2)FC1P$+}^PKyoXtQ*I^1a8Sx8F}>lx!=x1JMl~Ln^5-(d$jsnwb@Q30j$-R z3XImj+7dla@Q}$3XErcuXFqZ|%faVU*59u$4g#O(bcwnp(n2wjI_nTiu#{bk`LTun z<11Zku=ClwYx6GD5bau|O0`fD^_#DXp}8pd5bxzt(4aa;Z|K|rx{$!Ty+g%Didh_N zco^-|2MfobPoCEp&|IO!sh$nTJh{RlSxO8mA;oh5;gMZ zIWWWwCDl)Cl;ji1O$t5%qhnYf58M%I3Ug1M4Js}|sQF?HE97h^B)!z;sGgBIk(v<2 zH%#BJM*TKV&nMD2a`gGA9dY_yCabOnnrSftyF?RReQenIn6jqFXUd6ItXhRljE)FW zqp2#Fhqh7g#}Zn5w1j}3Nz5L3s%*J-a04zUM{MxnMGk%mb<+XX#X})~zisN0Tua=Q zjg)s+lwz^Ke}CQn?e6h}dy?Un zUhorDDsw1{W$~KC@I%Q>f2J2tY}64x<{3vU#(09ui5hXS1j(;jD%xx5b`uydNyM6A zd6rVSf%!W`-WRB1M_61<>CD0P{jmreXXz7ez4{f!fNLy#v4rr=syMjjumn*w_2KEb z)ABu?epd{r?NX8ro1ZE0onwklr#~-c%dFoV?zE?Cxc!FU8Vc#6L-}sqowB(IYN13m z!X*03LbQMu~bY+Ba<=q-zj&LUENo zC`Ub*Ct1wFq-Qep#qTbM?-trr@5u-^UGx_i>E%*A07|z*Qp$ha3;oIco)7&fxWrGrG-w+_$7U4Uf)!DA*r(tkoxsMKo+X z^I1GRQ6eC&^lMk8I9|cY5Y4BXZp#`iTEilW>1GNc*!mgP9;IlqiYGz0rU#>l=|kn-^=j zh5W*xS+r=BjA&i?iK@>G0-n{Ktx4Hk#Icx;+QO)c1^%BRQ>YL!()RQq=Fz^_>B?p1 zs;=-Vefl~5hd~US(D=fD4qBdnI57t&Y9-nVjOJfZ6diztsW6RYfwd;;;I+%sXPbSCja;Se`FXL-?}pKrEY#BaPtZux%*_6QT7;n(Btjb zNu}mg$7u3~?xu(9UFtPv(k}BhQ~|$203vvy82Mk4^#K{YTK7^KzVl2(lkADBam{%+ zv)7Lz6RQtw@KQ3v0EqF;`fH?1b&{^`Ow0RMJ@h%|YMvNZ7uCs{G$y;Aa4!H{k#DUh zxzQUb7C8ytes#EsOKHri7m_HO1)$sjR$}1AGjd;01LG^Ep)z(0O8)C5Iq+scUKtlx zx@^016=gTBIyFyN74*%AwI}@Suxn<{hDv=-A+xKI#|aQAD<zm_FYvW~_0h-}H?Z!%5Qwjr6$(^H9{GI`4@#m9U&o z&=Rc|Qw#|sgM7VWt>b|hA{%-BCf_lXxbOS~L-c%-b_1brm;SJ{T1)D1cjXLqq?lsW z1vmKIQ27)`7A{}BM&7yhC8taD9~xgwfgTeukhpXS#Vwb9~)Rw7qCh1KznmfekWR>|og1Xo{gN zOz*4H8uhg9d}`5vw?9MAJ%9#%AAs}eY^K%?1O9Rrxup9}=XNPYW?;s^39wUSXXW1c{N~F^$Cjx#T?Y3E_TDvKwO@L{535;9#>2FAE2~P1I|Bi|%oH7?Y|gM)@>| zgvIxXx_vqMSj6QCuiw=eriAW&b2Tlh82?q7yyIEp*_ui++Go_&qKA!vkx=%t;sckZ zoc8m*ld*^&bFNx%=U@)`b-$&7>?AtTaVL}J3P(r!rZ*S)L^Thh+9cM2BoTaGjMdn4 ziJ<%oJ!O+?9Pr_Glp{2ZFjzD{KfPC0*LdLI%{&ABb6$@6Y5BiwMO(=6v7L1&-t2bF zKISxRq^~O)>#)eitnB0oM=-mlGgP|((_hX|&xX2fjAoN63c~ku6@lxzXm>%pzBNK+ zSSk8eA|*GbqEojHWww<=KS5v0M$t{K0Cw}N&U!3Ud~l(mr9wI{8@3Rb_fN@H&+qCv z=^9##Bn5$RX7Exje8aSw`l}e=?Xy9byILAjXk!Ts%uLPV-u*yC*FzE=^a^83-N48vv04q*iNOP^hBp+u}R$+gmV+tNI91tE6A|nEGwGrvE&W+hu6@J#Y12#QKxV~(JTo9_%yMe7Uu@*JD z#$+k>9uoj|03-eWao=E_DS4Q0H?Kz^#SM4aam0C&*E8j!gY;cBtcG!9trL9Ywck@m zPx z7(M3xU*nT$)#14>@?v{}ExtTzkfI=BH$SD^6GtM8{0-%a&Q?9|smJBQt9ICFcgE-uLT z`l)?;mzp`>DoN-r_~G_L8JRuC;IW|bu9l18)&6S2-vbFVjf@J4Z+A1G0R(pVR?YH=)-&B-1m@V zcgQ*tWGVy8Oi%mDrHDjC^5G|fla{VokXZ(MvTM2Gw;Nh0E;Ut7> z)x*(?Ar<%mv9?wi=DFcX>|*wG1GL!r6n)NSUB_X@D+xyC3ck!`unhflLBkPiTWDHR z*U0_EW;PI_bT<@0i@0wXI&2C2xN7#e;`r_6qtXa{E!sdZ(6{NShPKny{mjS%_rR|aw^ZNS=*u~*ZGU=rsQ3mLMI z(GHTe4*D+vq7o4gL3XthCyS}FhSn9E=VnLr9Y!!Av@pMqX1)J^gxTsnhT`$npvaeC z|MT@LuRSBAx5B-Z@xNF8bJ=k@9-{Pro(V$P)0ale6$$&U>ZojKNVSD?<*e#CnEKgC z_<#SYP4c@+SblC|?$(UtBzJ3qt-3slhbQs*Gvh&0iPW~t3Aa)))&7{$`arLPJEXtp zEd}w144k|-zQ-_`q{9F7h^snGJ%H26zGJtO>&%kK%7=JM3N0nDxnVD`3|PxMQeJO| zY59JHk8t{kqB>qmmd!g@j7xlb7_WdXqH*aW|F0)_nZ_sO?P^lmQ}Me!Ik zv)kN-uIIfXa`UEl;Ka^52Kuw#uMRNz$nX$y>g3TKUmMUHJQmO^`#~gzQdv_S+*fzk zpgsySd4m|VOl$Qrym}DbrDR&$0 z|GW&464UX!%D~x`$la2s42UfL0d3LqVo@EZ=@)rDNTZqJd+Yo`pr?$lKzOh*)a{jK zFwJz#(IexrQRhZBwSO^|?Wo8GGx(wwTX9giqwg3_HgS8fwzeb4G_jtX>hd`FpGW_5 zNW4ZdPm`7aUodh?iqce5( z>*o1-oYeI_4)p<%l7%2@IL*risc;46hIwX8bl0O^u72R1?!S{H?6dqQ(f1lh(?u77 zw-@tfyVZ#;)rhpGF*PM0YlV;QN?53cNUn{{5B96Ar*WqZ$UoEP}ipFIxx`Hm*$Vx#PcnW`Yi=79EI!R^RH&l6dZb7 z{oO&z5PDl<>Wpe`_00Ix&kllHI&JBQDbbEhw`3gy{^p=cxs43nIC0GE%oj{)QRD{3 zE0`YWsof?b_M1^|(ArSWlKrH??3gHop5SmZI_-;x2>zAhH-(#1{uE#8l2pz;JrxzH z$LxWtL{^BR%w2_1UN&ZKC5n+Jx)F_y3dRroro$rp{<<<#i}?cbEh)nxXJ_R@T~(`7 z9{hP%x;EsTJ$e4mHHS;{CGiVN;G3UYX!Q<4lcmzu_O0`-34eR_y?1)Fk&A4tjZgzhMQjScDSpT?djL6i4kh+Kanf&L6DSx-94|qT*h{&Qjm*YYmhr{ za>(FBP}VG!{=4Gal=Uyw>#I&a#_zJ!0|ok^-bOu;M!uY*Pfc1q;`!}hP)+ICQmEcF zlwp@g5MhsHV%2i^8>a3kmwT8m<^JrqOD(F~^eZ7;?{|X%qp7#Rax;o0IP&a^H%zMx zj5#_Ekqg%&Hq~7{_pH*<`PO7&;ht~?0K|J>sdUS`3vOCzVp0-F|vqOU&{PDi11!iPGG3*R~MY|JsJ% zl^STd;r7_Yp?-s;*)(1@KlEL)2I?*(5&q9P3YMLw(f?xt?Jqh(*)K}VcQy){uAEom zDFczqbH2Ml$Rh!PjQut=v9+T8i>>Aygq@vcl$GXqKVzPok8I4rtx=aEXSYp8o3#U> zr$wUaC4{$JdecP{BzfHaRCy%SoTMZr3`jzzCY;e3H`5=6(8}5froXvf9zpSk+kA5O zj^LJWAMXU^i=lD+-xczgSYFdC31sG&)y_vA7DY>!-Zk-Lk&L#ZS0mRA^H(b`Cy8{z zTOV^++<+vN-20BXlTq1$#XJu$ZVZ=F%R8WuXM-7|)p{RFNgfT;UrxZ&O#0%+e@R-zkEmAKZUOWhn1!RJ`_b ze1I05Sn8#}CrC(fyUhe#E~fhn%!K+1e8_=a3=Q5OyuY%Dp8ZF^0d~`~KC7spuviR{ zx)~Q23=GT}HWv&P)xKMhJ8sYv&PZjb`u)*OdZx!GZnvP})MroXbiKJXMxggnNx3Ct z9VCW(VxE}sS&G_hLQBKLea4vlD1i|o&0)quN#?i8_oW8v3V^O=%RhsO{l=$`93ITb zO#fPD%*fm~LBN5i{HH4^`NaNl*`K!9cgpgjve#c3lOtMu9V3rNn>p3_c?!);`-;7o z63g&B0~|&_1x&Y0lM)eVF@c#|1?%OMs?h4>&Pd4OH8AP2#(ICVM}Es6mk-nxH<+Jc za4`7Ctd0Jtm z6NO^m_V-fI;WlAMXtRn<5(eF#PetbVA>mJG2v|cJH!~bXwQx3AhkZb54{pn}7&cg* zxW`T_gQw4RR{tx6pj~Vikj<(wcc9yLoZ~scqmtT{Q>&m#FNl}lT(BDqBCNvGf~E$?G)R!5V^BBx5?2%)C{OCTiu z(b7-ZqiVPSh9__kbGbl0wJnCsV_zWU?VeQLwibE$peQ$JO|=y>V{HO1wJ}%BmX8eS zya+W6oqZ7Jjra%k)0}sv7eecSSx%=B1>YyUf1~QlG?133S_$N(!T+`%UibdJYqt0la;a-f$Z& zlc$VzvM=X9#U6Llx#1Ulegs*7H;Yqie*hCaNLSCqVqU}Vx+$AhF2_B1q*H}RHLooH z-q0%g6+5AY*?-(l%Wo;1;uK) zI!hjIX+7^q@_7sD4(=k%JTVwN*^Pup zIA1rY9AjkU+v~=T50$d?OAn1$8N1cXUDz&x@7O7oRh`(haJ7Ib?IH%a7mQWd-zu!x zAwlT>oV^ffGkc^uj_(UzNz`GcZhYjpN&IFsZ!064_maoc)p#RX zNyrgB{ROHIOKtO*19$*BB!lT4CAmpAZ3Cyy)x@9ptN%jN)$*hQ!5R~}@}t)rn7>)Z z0oQ7faqWAidXI?2<I*;3PE|Z+9Q_%De|f zgb*#_0TFK_{NW$<^j2!q)N7&-;{?u~$=825QlDEHG*SkUt-thL9Asv2Q-zD*GlFNS zL^1wfti5Ga9Lw4$3?YFKEClxi5AH4@L6V@s-5Fd5cY=FxhXi+b_rVG7E`vLR4s&Op z_hj#V@3+3S?vGplx~sdZtLky7=M7i4ZB3>?CNgq!XYq3qkEeGXL9WCqL2iuVv`e>x zipvxK)%XHlOKkmr6>5ECrlylJjp#Dta=&!1sp^yKQjh>IO6cP89W|%Lt9KWU+&%p_ z`*s}#e!47oFvC~^e=+zfd}YiTd*X@=S&GQZEbx0`spMVgU-kKXQS+<7@1_;+%_P_C z=L@AjBh%ye)x2uGbzz&`+JTB*cBBRgy_$asD-~Q>6{fu;fAY`xTF0)Y^xhU|Gd60~ zoUNccvG60;e!$(s388n%k%!jYs>NR*Y_Z8Pa=%Dm0v7N4Hx&E4`{En6WGdWKovCx% z!(8F*CqSguO(yMa@r}u&7<2d)yU;h+v3$$)wozD#26rNV)3Y{Vf+=p6RX1)4hKc+* z^<}X?zxf(wAB%wJ@;1Y=;8UaOvccc?Kfa7XNkLNn*Y$aYN-L^D9d)EGQ4i2b=d_jO zlgVN`x8IYsG=OC~+f}h(+%kehvBTG<{A8M(Cs7wGv9auh?jP0auP?b&Y)bnwn3(Zf zv+K286V@?2th&AJPZhe>q#!TfiAg|U7V~fScRPtexX{c-LHI;eTzfE3Vu{ZVPlI=n zcr$&uan2NtZrqjJ>_%rR3@w@~$EX`##=!oYEy2}!7l!=jg??e5M2&_J2xhSeJEzwS ze}~b%uGBGJ`H3jApqNU4?=6!wbeAuE3AoC+yG>z2#h_$^u#q^A7@rw=-_hwEE83MP z;Q6e@Dwk?tDv{@**TJhg>_5*erLH0T*Mh_(84hL^-8cfS1S3N;xf9Jv%JKCsIMevQ z*Y$wTFRv3@ufznu@~;$4M!MU24M%)Sc$vbJik$(fqR(YON*Xs3=X9YvoD9{uAQskg z`88Kqmdj5P_HR=}kl|-v;=;)a3ak{~i_y|8<9S9y_%F}zGYQ!L=)8rifQx-Y%s|44 z*_++hPSM4+FjvG9%BU*XqPMq>U_i5Te>e#VESeSbMfJ@+d;N3f?d!}L`NG%I z<3h<)9a&ayrt#BfALS44;Z&|K;~hPJNL|b9+2JzgGKXOCzL+i+>c%?cow8%ui0|<` zxc2yto+h4IuWqac^fzIELjz1gA`5|gS!x(E^JVdt!~@4s@P&}MkUb(NXpZ(^$%P1d zg&^5cof+R>X0AERY3V&4TbpuDhVziPem2eCy7++PEtDKFAvZ4D7yof!IW*#!C#b1K z`s^zGu61EzZcIDte_~+sFyS$-K(%O4l&Pr64}OJ^^wG|0Y7536$7RpJzq zH~58)W@cM%>5i<}R_P7A8EM5l-d{bX%N~g-J(!CrkA!#TIA3MCzAnMB{};TS+a|%D z?fVSlmwd~i4PfRETo}v3>wut>Du-T9wOovi{2mF&wEWV%c&{K(5<&bsRCnbo&Z90x zz9$eHW4>ina?1c~nLci`+Lm8$R3mF)%F&WOU-OXY&JYD)tNvByr0V9MaJ$lZjhyBuV2EhE6whKU-g6V=9|SQ|`*VDSY3%%MTIGXas`4&?opxH2ipt zEqQCMr5pH%gusFLR-W;m{AYQlYx7<%b*_E|tf0yU$)ZIPsBfvB*+zu%KS5qb@F1@= zQRVRM&+9bkb(TsCx(90ijZ_*AMao$}*uYG5-(Z)M%SGyygcXE&*Cv!d^`o*-%c%qYRdAhZMc)Mu^FFB4{{6g z{lZaBnqrG3<*~HC&W)C0EGZm7#b|*iI zPJHLYmn&KKSlhx_1=r$izji&`ep+*b@uBQ0`3pTy>ffX7XIF94{_Da&XCtLhF1J6{ zrZ(??rCgc}Jf}u_;$|@X+%ynqhEdCBSYhs}QY60rEZQA;-&`Q90&CT6$8~Cool)2I z4!1`@^^bT5r*n^=aG|6>>%)&$U4sauL_U=$YAxX2%y~y>-fDU;vITsx^%+a6uUL3v z)7v58a**)lQ=QklaKOXb|^t{1rY2n_-BM+IDu>H&8p~(|*{3N7)_mgPohdzPUbDl5R(vABLrg-1f)StZ` zqfN*@o=@VpnwL(mB28HNc15NAQPF_h|+F?ooEoKI<}nw{hH!bGvce>ri1; zx!4onBybKMnI_{&uGf9gxG}}`*^ekHuyei?F+|e*Z9b3Cd}AhI5{GB>f#?k{v*B@< zu_KfAYJ2E<#8B&>i z=S`1V43QjTqmbWZ&+b%ve4u#P1PAU9hc z*9d71x{XbC@%-O^u(2M9OhuA^^7!4ZL)Myea|y0Tb0$c7^UvmI7uI_2erp*&)vdYi z-!hZdMz2JyL`=XX@F|-J$-Zvvb%m zmdqMi2Stu!*O*cXMoa%AAHDtzs|HK~Z%J0CYA`eL#B1f=u6b1J81=KKAWI(VJjHc_MQhq;Sol=&@4{(WWiIP+GLCh3Hz%< z)K;z?1fsw25lnhJ;?ezJtd+euRW6L! zePqG^dKqS5VUP0mpJxMJ`y_43`WDleUkwpvmK?f+oroBwAZ4gmwptv(qxQ`&86p+z zHlLx-nwy%HJm%Hih1Dt7?hyX{1(;A@5`xOmZ-+(0cK1Ve3l&J)<%bAvw}UznA?;x* zMnui;$X+Oy%T$Pj7Y{x`9LnZ1F=}&6aMqu95=LDJ?%C2HCmQ(9?sO@)>VB_Op+jPk z)I>sw{|_{7p8U18NO-~C{qcw_r4($wMIC+1+ArD*7g(xoek0^ty&pwG6U~?2@tn$Y zI<8`Z-!PaxJEbMgX}_1nEi$vL<+tUu>SQ{G#6KkdrTr&%>JJ#o`*YF3 zBP4f#S$mEnJh(*YdE|(n!S`AJ@%=N_W5b<9{s^-}4`4{Ml**z{tFH<+Xx_(Kw4npf(aip0l)Rxlhfl63!_RoH%!CLIw7yWE5e_6Gn81N30^Szms}kJ%Z76> z;*%VchXZQs$H+F+=8R{VT$zo&DO;8}*T*dp-tGuFdK&Uyw`RG@c2c-IOusCS+(w0Z zN!z&|5b7R75k<*m`ppW!`G#NL8J~#vJCpP*uh6)h?OB?Z%V*qTlq@7D21{i! zolg7NTd#&m+WfN8a@hdbsvf%4mtuD1nJ^Ob&7&$uFLm|;M#kPDg1`hotWNj1s)I6^FYQd z?!DXBaWe&&0X~k`QR`TH(PyYgV(f`m*yN#lS70f%H-#V{tpIY)D^YCX2Lb=d?R_RVurV@T@|r;bo$sy_tWgeJz)%Xy)dlg0AggXV(5TWeBlRi?WH(eE7UIau`fm z)%<{?pd0uSrMQ{~8%T>fjca&G`tW~dbJQ|dbpL}VA0G?wys#A1P@W0gWS7Uf;$>DT*Z=sL$R6E!GuTv0j(Z#3UDPZEWrI`hByz zwnLE?AZq$PF*(V;6_u7&I?eJAf{5GG-#<5#c4n43^g zP%*^`e?|XluXzQ2N(zgL2fWPLoPgoqb3*+Fw+13Q)>(V>9!Sh*Ob~nJS>dt`9ygi_ z41Y@gJLuEWHcYl5b-K6=c;ZSJg~c$}=*$w!W%PnUb)?BP77<2_$DXUb{jnBVleB7% ztF>4;+tE)-*#C-)tZxqGwAG02OYr^i_22rr=(wr44@8(*z;I+)_1Qp3>U69Kq3WvvtReq6PwSyWi zk;wJAQj^JiE3rbBs&#qHHu;AsMApd)IX+P*UHK#C6}o?ifldE*2d-mc<~#kgo+D-w za(jj5t3|fxR3>>a%TM|RQ#zNy?N0Qz3@Rcu0vWeJzyT(Sj8+A-^no+1!?Ax_iLb?tq6(3DkIM>S#iKU6 zdN7RrCwgcaeicNYLja$}c1_$)(nJ%oFI}-Ayf;ho`dHQjS~+BQU3EPmPaoTMd$-+$93yPLp{<}fVR}?E&5@U# zR3iUyv-ay03Qp!d;)Li_AqsqvLPGs!c{$&SctyOJ;e1^DGx!DkShmH|WLwhbhS3>f z6|m#H<&mZT_Vj#w z`Au0<{7AdzGYua!-71IFpn@g<^_>$08)Xx+Aq@JTJJM1!E_7R`g^<>2eRtStG_2)QKZ4=kLnkiotIKRPQveKCL5GVzaw2+0LjB z)K(B&`pqV}s2Nx6oqRn8dni$DaS<3Pev?-H)i+=;9lh2~vZRD2id!cXJ(fDYO%70n zkdL!A#63R$jlU`;)CiP%{y4TIrAeFC&CUg2*_D9+UN+ z2Gv?{ml>4%)*7hsEE9X;rQUx!UX{@l@S|fKWJ3Pebhh)8MgriC))7JVbIyuS9?droq4YrNl6$9I%N%%TAsLj8y!SwS z`CmZrxU|#p;eM^U&tkd|)j(R#p#IXduR<6JMP>8xs=SqxlZ*2gSTnY~UL<~uAqUwp zTdiU8dBgC$odF%p9W~QM=>1+P?#gQD1?g(pP*8KvG$V4dIV_egIo)IlZMnc#PhvScsMT z{P9%f{VRIszA%?(nXe!$>9{1|@sowag)wKy_jzFwcgmmNaq|eoH0e>Pr(ehZ_|a~% zdn5IxIzW~qEdbY5lp@+~XRNviX$vWpO&k0&&}Hd1_(hi1#J{6D zK|=h$4b$>k4~a`Cb&oClG2Qd~49t;?+gD`6oGB$i+uT~xv|{zj@x*v0o9x#$g@uh# zU-vQJ!__aX%IS)f;ng<$Z&mE?a3jQAm8o6B>C0b7Xs8DSf2O45QfvwNZ~OeI5cb^6 zp4^SxAAni~_k}uc^oEZUFbQi8RkN|%@qLtKBGxC=*AR=V;LA40H&RGWBlu`IlU?}p zb$511=?`Tm2`OwjM2SFreZ$ms$E89?Ee%gRh!#|U@=ptHxR>|6k6mcQbVok|t|N&0 zit>jlmmopq3tK7V)>0EnZ)(8-UBaJ8u0Si1abtVFE;|gd-<_(6Cc;;}n0U(M`n_`; z;v!_1=pCK%rIR|l;?f=Ys?o+C%dEa|c8ySS_E6`0sA(!|9rVEi=?LwsxJsBnTFL>S zkax88i2YS>u>af4DGxfZ6kw{m(ApR+o3Ek~Ehqp&bwLem4J@B9UC%X;M$?d5r%4K`eUQZ;wqjFbd zJ0w%ZMVuwam(>UY2eJ#f!pPfitqGn2*4d4AVrn_?K-OyPCqa$?)85I6rbOGP1_M3A z*{tfQ+~w!UYr>hL>1YEEb@^Jo0_{&WUM~l={!BFHQ(8?}77^lQ=O8v4R(d+(W!O|@ z{YgMQOh?yVeGU<6P4fGW6a9{%WL1$bocJ*d=gLn!Hq=Qv>>)Nb6y;IO3xZH8 zTGr8??%^^1DGiO~$f@$Ss1n=e?;ROyNU=}Gs|})+^i41A-YnHnw8;thZ{$>LcW=;5 z(t3zctTx<{W4dRA z1zed(bM;vcXZm`Bgx}=DVw{nK1&$ydoH1fG8u)RdKFFxSX6|4<^6<)UM1`d49u^qh zuRFRHL@v90LNk(Fm*=@oFVAooYs7cZE!|{zgojQxnFKHozjJ~l{`8j){R8gPNmDFB zf_o2_-pO^g{G(}gXvxU8h@1nhR@L8So{y9$tI(z5;ruiS9oG+)BUoq22u@%@8PgM_ zEe88u$O`Ur*gT^Uo=bRPRI%}^qFznIa$@4neO1ezE+t2PYxT>Wa}*<2lxq6ZP(dr3 zCkaf%l4;GVSd8pz4!@Tz;dq&g_R!#pSMK8@S(Xq~0H&3h(=PA_*S9MjP9Nl-d%^A| zqK~w6zx}wPVV2f^xn zGHCSBbvvyZdj;+#z2hd;X!R>=d1cq@0-n|aO^ABX-i*I5d{7{@=6{$$6>R_`%D%2@}w#Ad`WW3=##2j zR$A0^fh>`T2?8jE^;Y*8I6to1j95O>H6aDXd0E2)fN5^&vz4)Nda?f~TqmdQjt>hK z?3cKhuc6>P9wU3an?+iNT)hc9q*ng}vDl~*NZfv+=#5)@4v$ri4BBI@cw+aYcz^o& z#fwlMH#*Z~558;U@;H+IAug1`>{6dl-u`{*P|0QWY#MvK3f34d9rdaLTA#i`__&U= z%*NNAd)$sKyJmU1oyiU@DcU9el4b7#ybc{LIl}tzhv15*W(G<75;OB32S&SXbpiKQ zn9Cu4jqdiV8FLPjr-hTx&49?-ys6S-McnM{*CwfwkMmkNal=*&hXU;6L2a#78HJTJ^y zkyt)I`!K27mPU|&Y}2@HN+iz^XWJZHag*L}9gX!)Z05t?uVA8L{D2Pxy+7pdyTq~W zXinYKFKJw~yI5g8pGeJP8j&;JfHcXZ-eK}$MKRiDlh6478kgN}nO0#MQy;mB1KBD6 z7!%P!f{j@Y<5%mCGXPj%KRhagzK6VRsfDm?t`q>)`C!OTv!CkzHRy}$ECeU#&Dvj5 zKOUx{nFgx9m%bkDq@%qU^75KLU!_{M@A`al3sSy7$s9Xx%aMM#i2#=-iLQqpre1b|8v)APv|O z*kiB6f|r6gl9!{LIrsp>VK@z*Y5>q23LoyOAZBZls?PfqNk@q?b+*68vgR}@eCKH(|vSp?GEiJ;4sIgVtE z)~_gJ2>a4p+6K|0=2Ey^Q2MH%=3DE&fXk>TD3PNoa#IW$zxOt?_8MaWhCW4*th*!0fwsZXmx*UgdgD(n|8vVc?Z+}=)E32>Ig4e98_pZ zz8)l{XX5HAvXo?t(#bJA8GFa%af{qvu+}4+^E7yQ!_}kFnzVA5bT-vL*)CD`Op$;E zaJfTpx$Q!QdI_%HicV>DI}i8d;mtx4Cm(gfLhm}CLVEm>d!P094hMfP7MS3Awu?+N zx`WZF(R_rStnJ(4NUqvU%I9;OT$qV8#Cx1O+=%LVrLBe^(H0ckzNl*w2b2OIy4m(+ z7)OajdeFW2qC1=;3n!V+k~Nq-?%WcOZ&u~J$$j37Mpsn4ef7ojkpIo0rOV%I zt7uD#LFW61xr7XKWj`(n{*ZCyX3QXc$y+VtLp6NK%l42_^AgR8)4=q6 ze)c+VX@1}$-F(@(^iu!1c0;z{Z`%QlEAs{Mso-+mbQf@4`h?(DR0Z>82Hg_LKXm@H zj_7+*cq!(o(m)}0uHtPBszh(KNaNf6<3mq9rybv9lA=A%ldWNEv=rC5Z}o486DX46 z5>3~-fj|HUaLxkX3YKA8&@qrFMHaw09g=mKkRV^Uqs>^yM3FPI(;8D}zqSSo%)+E< zMLv8Eq}LYxMe5O(d4qsA+%#rbz5&z)w|R3x9Bf{h%qtgqii_v6TU2&@X|FrApOU~? zIBKYTb+d_DE$2Fpb_<@92R^dq5PGk1c>0N6jcf(_6`ZH`bS{7;S2G;}!Vk0kwN=WN(8hT^c^DySD{4T3Ytd-w0X&6K6g?Y6GCxE^jy=F$gO|rZMPNg0OZ5 zjx<`KT4JA2jFgl@7v5$Au>^Yiw)SU;c`YF@K|9}}=;6gtMK`hS5&X zF1vfKO4Rdqa18l*xqL7M=XQK^Fp$s~?zU`AGr}+v4ndGA-rsIms$&>LHDex7vsXLI z^TU;c3U?tPpSPx8KEQdk(a~0fXo>HjPe&Xp&y0v4A|H}m!{9{NQ-LEW z^_&Oh4kbur))>6V>e%WD76G^|1Pk4SF1Of_NrNMPNxSk&j%lbZ_5y@C*Z9a>7V5RF z`FApt?x@eP@Bu7FL#0WL=jru3vP}_ua$Z)?vMRJYmrI?P2GvJk-riA%a<(eo9LJ?d z>mjC{vho+R-TaSN8wj6EuxVQ#^Q8nt?Voaxrn{k3e$n z0HDXI!B}n|uF7r7Lxjhz#bp-LkY*Qa`08fjyJLuLqQ)rnLpesUez836d}2bvPGS$T+pl3ghqUfL)|$KscX*@Gc zL)?Z_glxC4R-p8AhgLYanj z2P1YU&O4pjLSNB;qRPkW(Yp(=2~kUqp?#kciI=`yibyJ^b%UYway7uh63Kkk-s z1D%1hqVGG)KTHTCR>o0h5)H__Itqt7-q(vfz?GqZpV;};k5;Y_2Nu`P+FagN>zQZJb?RWlq5osWR7>nlFowxwRgT*=R7r!&os^>D0ulcyy>>GH9Xly( zT3nZWXDf;B1RN=jBBjllnbvXl<2IaSXRQP5hb@t$B=^g7H+UHqy>NtKId0Dz1)e>n zo!rbGb~DlSYjX<8UGv9r14aZ>ko&|psBOpE-G4rDeYDOTX$x5rUGy{W1AxdwQiUdqkNODWG0PsW^v0PNDnm$VY)o z4OMsR{fv}fS$5vXc-WPi7?Tp_Y zBpV-n4)$ga1%5~r^us(RGqxG(oT{cdmlPnGl<_#9r>7W}<0tv%$Z!4H>r!Ov7YU#W zWY$+@bZR&f%vuSKKfD!M&@0$cf;RCH{zcx%1;N5T5cEXcbWjoadN<)k$vF~Vi{1U5 zlmg$SPU5y-**LTFP*ap4ixG^!;!^h;oR!h4k71|*t^!?mbAXKxM1W7shw_ zaj>!9PrbzX>1)DWC2AqTm7>6ccD|PHFp~6fSZI_TNcyVLu%sKf{`CXY= z`HKc~t>!zR9TO*>lF&9ZlB^bA(AwvIET%_h)EjJ3w)=7ePre&Qj<0jv4HbaZqdr_D zY10b-g}BBicn=4Rgu}WtZpMPp$mY27`_lN<9c#_kA&&**WzguxAS24ueVqK~(=*=k z_SzSW6m5wGYpY?XOv%Tl>y0>O_Lbqvx$zSK`W&01q1`0Ovopp+>Gs?J5NEf~ar@!# ziHWDW1Dz`xxS*6^=&NyPf0H>>)_}e>YMzDT;9_*r{%GP#z~STheMhW)_#qCT?HJTV zbF<#;DyQv4VVX_^nxioFi+u26^-USf7ggopwZOZhN{g$uBbw6a)=6?I0OFRus(8|s z<2(kTOHj++CGJmICYn`Wlh!affLl9}#z{v5eA-5kydZYFdi7@~O}5p|N5jRUN$?Z# zx?<$>Ga$eOa<%JmU4+&mrp)-}QF1@zZh`FeyOxwl!oP?%~V=d^1fJj%Xc=?w*M{CXL z3mqe@O_^#SyX9gOLPvm*9<{0djLDs{2Mgx+PrLV3gZ*v|)nE=I0HS=R4~vvgU8<9a z9Vvf6$JOx84Z&{ZT(w6BidF3*SpFCeMh|c>^7g$KK9#LZCn-iRQ5*#aB=9>ARXQrw zJ$lDzNckvLo-fFYi&HB{R-$^Y*pa*N##PT&S)B^td-A8x2ZXzE=WJhZCfsoTWLd&R zR6Vh1Cv`&nB;TH9%j>dxAzyF~-PYpcS@ovEP+Rl9dbQL=(NR!+N|nMINYh~pTB)EA zW(Z%1>wVM^d`a?q4I)sU6aCB9k;$|TDu`AyTS;$;5nhddF)hK)x73i6fb_Qt$T0gB zr%1Fs2l+RhP$W%FEMwWPZ(Ei#%l%=2OZJfcPYuM6f&)%R3S;}JW2Ik)zhiFKua!?W zR11%bc^<~*YrR`L%?}Lp+dz=PK|>1esdQqUS0)tL_5;LR9`BB0of zPJkD3}*=H!d_P-=EjoV{P8OZ>kjBnV=JLgw z@=2;IM1qN^LErjN%POM`e0@mPU|xJ`>7HHf`xjfmcKc_jR%eKbfkbB;UvkCxbokCU zODuA0i1kV&2ip{KG{H7e!#yh+aAV(69`k((smpBmC5dwJq2f%X(6bDaJo=q{{}0|kw`?vZ%RnbZ5uS006@l9FtRKq2)k}cq za79b=#oX}yRuthtpqjJkQj%T`(@#JW6s&HYB?>VVQ84*SL>S^KzFbuwZqgn8Z6lN5 zDOY$7tV3R7g|z9w#RTX75fk=)$oeWKcO~{>P?xQA<}-VoKipK;Tsd9zue@_=)x&8o zyHt-io6I)_Lj_?h4BbY(uW>x|Cmv?Y4KoUak>pPmR}q^_80pei5l@R}sMQi{ogBB5 zl?2x1WsHF)Fk1K~*^Yjl^;n$f@OduCYeh+8x0wEg-Q@5;4uQj39Pb!~+qk&TbppR( z0rd$Yl@^|5%`NtmL}X{>+7gO|FkDoUPCXVYP&tLSp%X^?RG@o@hpA9+leLY3g-zh` zd}Gof17L)SgHy(^*(FbchOP%hx-V`_C@+16NBXU&D2bq2KvKB6I=DL4Foz&}{AFr~LW5BRWdTH^u!6 zC}!el0#24j&1k-Dk|P6-yW-F%b^~7l-F~nMd;y4E2<});27s+eq20THR-+G z)=;rkCb+sWx_f$l&3ZU^Avt*w;=C;bO?T6hDXo3)$!36SyLwH_%BO2OxlD!&f)qp| zaZAOx8|BOFmY5s4Ui^Zc$-}fpWb7w4rib^yL1cM{0S;vX0ua;R8bsTY&fB*!4R&5@ zxb4km3@PtK)Vt+~`xlNIIH3=sMPD2e@qZv75N~}E7gG*&819GK6m(UmShM|ZEy!yW+0sk9-FUVP;&6hu)o3_FP&%(0LRHUd z-Hp^yCtafzV-gx))#-(To+*;M0kdpES!`@>c=EBMm!eM8_~dpj6_~DHoM2xawxNG z`=H#5Wb0DkfR5<91bHX$%6LDPsL_Ho)_G?*vV`dBV0`?AX;|AsTR_`kC5vJGP5PXh ztvI-i0pr_PWGT8Oa{$=FxZ<6me% z&M+e6JA%_Bp>g0-^Pn16)|NTeje^L#NLFm-U|P-$bKdB82Pr6x8xv|o3wdzH`FI5FJVc3a?noq_l!y6qS$ugKU;MjDPBJHOU!&32%m z>)mh!G%Hv|1Z>@Fv=iHC#ksl~eg{d?uGAmv&H7B?KwYAS8$cMna#56>ejIP`AC0ss zI$EVdWDF!F+S^yr)<+{@PA%sdkd;sUA|B{;Ncw$F{_~E~3iQQpJ;m+qaGL8@khX}& zj+z4`yz2xwV#7bj18Dh+2lYFxmi&IZvz$Csi5YOFT?V~DBiS*c188MI;nu~EN-8=Ic7k!b%9mt5>9|NiBGF)e1sP@TUnT@fa7vm>M>gB5_a(ExqM~r?UNT=Gws2)>5Pxe^;}e7WBu*S1cZmDrR*+ z;;%{(3sIl08xO*U3M?41?kDDlnyUJMg^K*VWU}iI68=6A9PAk4rW+{T_jcIho)m<+ zg8uV84k4B+f^A?^h2sLsEfQ^wqfG*fR=i6t+0_~dLjkGwYAc#CtdXb8Y~wHMU2Gli zbd=w+c!Pyp0Nhqb`6j7w91Ccq&Qc{3cP&~)> z53&agE4RaJtmE!J&fyx>Zz%|uH)mfIr4AK%bJaW8Se=s=D~~AxBTs9x;HEP#jM?X_ zGcM?-)}%=4+nxf69Z_krpWpwkoN5F|yEM}Os{KT)Hz^jPxP1mUp5`1oMMsKkzLk8_ z`Tu7Y=A4caJQSy<({|t)<@Fwnn33IK)cI?{Xq~moy(9D=l#CvH#oof?c%!a|aho@|m*5ke$J`MdWFE z)a@3D0O22}V@!SpOIj!I1aTJfED2Ik8!&v&c4FR=bt}Sgw*@Qk5-%Y zoB%a5ZznyjdVBpDS;-1^`q6EJ%-s(7UZP}{C;gb^Czo2}60n-r+!-)L(NT68^VrK; zcAXjQ?QL}9xu$k5P3<05gN5_Akld8f|JMT$Ow;1lOH9XOp@mf2Ovd{Z5x&#KZH}R; z$r&N4WUnmay-8p6&fOgNc{T77{49c}>>OiXstQPi9al|4Y2i^k)Z16v1=ON={HAY= zw{9n?53ve%lSUWnczHA1?{g5cFD90Y`nE5PcExIYLl%6TNhXXbJgrZBu_olX7+S+oaIyd?>aLL#EQ=R#tlC zl;u|A$br!+=q1Pn`uEZbd(266Z8xi4|UNeWyBf6$4 zv;#`$Bx3a%!GS}j2t?qCo2CX|t-^m(b>)m0KdRK2@+;09Anl#i>5R#mGt@e$vQBnC zd~>E&Lnzt~Z6rYH%jpD}p8E5|p5AYbX#-^8p-WXIt+YiYG;TWb)D03O@RBfW;dZ;W zRL)Q>}}9|{%pLCc70RRs&GnoN(Od%l+ARzUJ44<}lo zeW2#)Km`wZx(?q)Ddw%u16GBXP*!YB+`vH-H;eIqF*?S-h_-Ct6FE~6%RNFJ!x7*7 zp+lSChH#zRzC80;>TCQUliTB)HgoaKmUCAjr0$=EFF`D5C0>l4Ih&P~_&85mi2bP; z0pn(J6M9Pq^y zjhl2A91N$w<)l6~@~NP%_XRF}{4{aIH*fW8^M6V(sY{5TthTe7o8uPXq?m6+pNQKB z;N-AHhJ25ug$D7~cnVKp0YpxgtxJU-L5W=sjY4qsw_y!As z>o!5W0?5P5K6(IUk1)y}wlHVx7`?@g!j!0~*=y~9DWgQkzICq3ZUM#LBcXzvcm+Ke zxAv}KR(<{{eJ5P3CsXBy(|SqgtE@}kZvOaQCkFx(wMzX`X+QYyzG8GE6B?)s6>o1U z%f*r{Kx6E#&O$g|fT#Jh(GR>m(qptU@pT$P2rIV@^f5Diyqw#(y0e$jjcfs-x<1_G z7y45$c6FamX)X`u&0NgdQhEyiE=H4xCL^L&K&nwfzlChh_ z+UujLI%`YKhcsD{01!{+z+0oZ^6Rn&$!oje^+!6R?!JUOl;;kqmh zLxHC+9n}MtCP0v0V3T-qNn&$EQ+#;47KylsWFg$F1>G)a%Z2aUNhnJvWAlBOWoSYb zSx-n84jJO@%e8y7vU+g5RnLC+h1SFI@YJ>9q(BRMbY^+0jCCcj%%_VeQ9A1^Sm zf(gI4;GLA#fdlSs_1o{VC>OUwD6cOb*e*WJf0^4=$JC!X?kc(xoSBxl#FOj$A)DN(C~T<_YepT zL|6mzzWwombG?4J>m_zj?)duq=g_VS^BmjWBypVNkHrKP)REB_N23-q=$x%r!Kn7h z%nbb7)oTl^Ak+9(NZRX-ZVunlZX~JDilVQEtI<95dcUe4Rh*WJO21|cBCpMFouNl` z&i|0#HtX{i>i2 z-3{rCV3jRsBBS|5aQ|)+BQP_z*Ywb=lz2L=j_lH#R2^w}cCfFCxA)lfs{o|-4W)E! z1A@Vr*Ah=KX(V{h?(>59ElHZ4a$%sQ)i5(rYY|Y(Q@H1?5NXZbQ<97sXy<32xtjfD z&m3E&)4DU$a?9>-z=E>jC6usFFm&Mx=NRAnLqXtLOr^)^6aUPvFg-eFXWU0+xxKa! zP3+NgeuQz=RBIh6<$eGq5RHLaQRg;0+kTsR(z8c-k@+!QRq*C}4Na5v60-I*e$ZO5 zpC2B%Qf7{Gv$fu>q!_+UH@%GyweBfkQ?bEN+?lSz&2@0RRACc!o8}lierM7qaVd8k zV!`A;1DBWo)8f%a-XTjn%z9A#>{=32%PeCSM0j{?;!`8o5M+DrnqR?@1?lh;#0I8U#*X z5r0fqYj68*MY<&WsFS+Y2F86{Kvp%zH;AU$oR7hxlQQb3-p~g3t##n^x$yRUe#xF@ zOt)KIV<5gx;zsGsNm`@Bx8B2V#E6+SdW@jIF`pW4&}VpkA~9h^#x5jRdaK<{t{pl> z5PUjK$i@^=$=AwDu0&qKN^*npp0D1fr>24jYNz)vu-_jD18B>xZn4VLjepL&p(7Hsu8h!?th{(~QPrhCAnjM^?lXX&^; z$UW~|^Kt8a_h|0^Kt5-xY{cb*y59)`RuD>0FV^{seQy80RY>Lzk;X%Ph{-JmNX5h1 z#zxfCfUEKo5z$JQ;RYe$&yNk&s~>^9ZSR)eZ1%0)Ki}#ZexG=nAhUQg4!RY4yIJDi zXu{3+d)L8Y#DM9^?eIg@QyR$~+AkF(tq7ub0m;hw_fOKH^? zPcH6md>%LyuT-Ph-VmtlZWe#PCGb=0Kw9j4`Xe$|pZP4`AR$+J6AG~|h~w)>*2F=G z3KoiEa_xzS>5m7CCALNBU1i&kp$IFw#zlxA)Eed1D=f4k{tK^OeH7qOC?A1j@5|`1 zxe~kvQ`j!BOo;%85R25*#j21RVXDUUX-C-HRxN#4M6imBvy=>Wwdj~kp2RG9hRPQ| zqKWi@Tvh=@|L&3KJ;`ipj6a)i-+gt{DAQ<74|;jXW!Q5UTtg+8yvy3c?CwZocb6LS zEvVnKq%X{S{V62hQ6%HuQeIUbHL!Iu8P*i4YK7c9@OjHHn=u{Lm2MQKww&!z|C7#D z-`2AH;4mXkzwD%ayc87G9lznPUr@KiQRbP%*D>@JGX0pv*aVIY=;{F`bJjoQGq1vrf z9r5$OpwJ!TowLMi8%r%;&BpzQF9(75(|up;clzdmKV#9S%2DKan0yzTHsg4i7@f=H z#&iGFVIj@Q&-MSEY;Z)yDFCWFmkSxM;63Y$43l>wd z(~^7`34EO=zI!T~M(VfAe@uvRDz~h<; z5nJJ+Z3Z}aTE;Zw;D7$A?MzgIUkEvO7ja9;{VT#0yoJn7nY z{hf}&=f_M@K8PElx07p|?*)BYFcU)i1#G8TnxxvZRF`H#UX1`S}-F&7|-$9ea>ugPI&w0W}?S&d5^w&7i&AL0~UUIKmY1k?Og;#M+v$z*^P zuZ+4|JY@Ha6-yU)OO`i$4d)aZb*n!@t#poch$>6=bujqoIM@_;s+7}-;UYt1lpQ*y zvs`T{?@~O35gKaFGjtLlu{JXc5*Q(yFdh4vEt4U-@&Np>_>G9{aJ*x~4SXDFmo0V! zFzxpYQcvfM-uR>1)vzJbuMP!d=?QhCvHE;bWLCZ`F@cLi_jKj7IBhgcumdY*rS&if z63CY9qAYUQ&B9p67K2FF>R|m6IX?ak$P~!Kp?O^dk|fNck|61IZS={YU5un0dEdIH zUuQ2z)1P_O{SQsk?rAC_ia`r@5FW+s4N#=YQdFuAN4AOkx1s#ortla6A@6eMP#~`h zT<8!g>u~3X=iuiIL~a-}T9!ArvF-d1;IVYM+znns6ZiM4vmha&88k`%js%`VE=LN6 z0t}62@;9pHzUjcsNr+pZi?EKSiGMN85J;HG)$O0C(g9)z=WzlGpPpfhA}aM8|O$(DJGv1sg5m6fsw0%-$%NH_Sp$szFyZ}>Wn z(LL>#z?-8K`ORZ8M4%mcXFY`;Io@WgLPr#9$j}qT9^We%wrgX%YH?L`t^^pF&6&av zHciA>#{!^n7gn6m=Y_MB_M&~Ue5oa;O$uhNdoH7&wx&fc5U3VCsAdx@mR=~isb!fG zbF(dN0<*aT1}&YHu2b;Gbn?0=4_hQHWZboZZ8(I1F6;=Pj7A8*OIdgB`=|3V3$9Jc zub{Q!nVRKvvi~K%2))YCKeW>xYA$qDs2sCKG%t}+nIp|oX62-cc`Zj79|Im37;e@F z7oNSlgJ1qlr3Fl>Lz6GGvGSv&FzKbSjgo^4(`Vkmv~7i#(eDiTha=odMfaO%`Pp)yW<R8({nMR_$Us#RC1 zsQ%frY6afmk<*pH|ESL^>ey3J(SIQSE(zL6zmbZHlZqmLK*RZQZ?n0B=IP0ap;ijR z(`{*Ml)SuJ4(#{mJFRhW<$rM)9)TkBL;R+N`GBiS+U!+Jd%XHyzsd0?RN0Dyl)RZQR_^NU7VeF@bMM57*Q3jc=!JOudc2bDVO1TNoMlb$vaoNt|UMFeR-D339b73 z2mF7(*unq#Gvm5-j#n4&zVJcMvs~t%A1|k@Sn{7=Eads|^JkJj?LYr{&+q6yah@!{ z|NEZxYx%(c`;NXgcff)F{2J9uhL!*GhWCdL+9&?!J?bO3Y5(UfniCJS|K}}gpKY~& zCvS21z3-T||IerBe9!#PJKov0cH3AN)@R}OI75;@sPfFO$Kqf)o6eViSN^~Ab%BwC zgX8f3eNW8j!zYRVdFZ3sk3-k~?-V|M{FD8E-rK{}{QU1*h09V>Qf}S3bF?n~z<~pN zs?WT3t@pXhAsbfYe>#kDt3si1%9$S@yvOOcsh5UHpIq;AXt!?K@k^K9kvuf6y0gA1Mc^6ZeEqhnB9TwHr;aA12+UA)fok&f~s0h6O$ zfkj_V-~IjD*=@LJdqBifxf_k*k4nGfd3aDNKi%2rINJHeq0j%}!{|dk>tn2&GFH>m ze=Z&D<=VANS=g-9kDHD~Api51`FX4S_=D^J-LwB|rkQKW{oNM1EdsQu%@LG9Wp8SW zKuM>52mM#B6XzTUTJ){z5;eOjBZb9dxAXs*FuuDFjIUpF(Njfr07@au<7tf0dXItP%Pcmz2v#VH3BD2yu5ENtG^))o=4?MQK5 z-QF?^2W9H9grm})J$qtx(_>e!-}UfEQhE@AK>O$hmXp?9MCxvAK4x zH8)}DO8OlV61t+6)rD!x{PGIcZ{D2v_Y$wn$V970(lwe5#SIPOAM3X4*>kMp zb7)njeMeh&ckDmQR~NRn8YU(twm*9KkR??=-BL5IZOw@jCqlH>u3fv1nK{C~<8#rM zFRH&v9y~}&vbk06@8|afA00_wO+%x8{J5W(O-sCPx@8PjRx7C{Mm@@5a@0a+*ZLq{ zbp>~K_n6#cl`}5|Rx)hX(9?TtSsVYSVvJ0mXH@v1TU!=)5a-g`Btx5wldsNMkCpt< zjMM6Bc51D`EfW$`w0E)XJOAW514km)p<7a;o3ZrO-`-vw>j?MIz4OYd?pW1}qp6Ks z@mwEot*aXAsjGQyYl09fGs|mCx3Zd>oxwc3xyvqTChFAjnceO8_ZyF7+_Gw%@i!c7 z9q+k)%P<4!R&}+Nkw+40KYaQWi*e}YTufKE!xs6o!1rX?iC7Ja`U_>%pP%knkITA_ z$FHDci#Qr0rgLYaw?REb%)0W<#=RQP73lg}^9%#3Q%nvg=w+$}Fk|JATNSgylLaj* zx!oqaqE<67yvi*1+afpmaf4y!RR);~FY2|WLxvtRn*II#W_cJlxpTx+D}#M|>6hO_ zKOMU&x5dqL*CxbuRYk>NqT97iO(TXo%9HBrwKWsWdf0LSrQyyX&RooSk2{c+9z#h3qZ2d~+hnK+I}BMe7{Vc=mOd z!tlW-3vsQYsG)Js?pN_P1_p*hhYmGJK6c1-ok%2GC2YmeNV#m>x#p}a`;NQ1ug--U zb1B#*<;`Z@-=iOE`}0%Rb6=SN?mO&~T3Zj_6{(BYPC3XfdEwHx%`!4Fjj86ow>I$a zp=3Gs++WSSw) z%E-vbCVAm(Y!Bij>HhAMk7k6;KSygN=pqPR&upTU_YMps;Vs1gdUlD3Sj{-40GZj} zCYT4F8tHQ_Z~j!6Q?ecyv2=fVeq;S^-Fw}QtsZmDQlURbyQ=s!V>M!Xuqom&1G5=b+qc%RF3uQUtp|!J9g}->6xCMKFg#WcH#T?@57^`8evi{YRYY7{yaVYkz4(1 zu>^WLG-f%*1+P+jvVV#6-1JC51cU5!1s`Js=9BMaMm$+K^{8XP_IK~zjp_H8=+`Hy zuXh8ln*5R_OR_M{>-i0KQL-+M#VXupF&Ynay{CRSAVkXLr6!jmBCQSe`p-y5ltp-2 zA*M;fq4No{?(*f!u}8n)HqJvoEF05e9zTAZX8Th?Khy3|!07DMK%C1+d%M*>%jz9* z@_u-{Vx%6Q4g6XM4_*=P|Nh5J8TjBSX`YJ5oJ^?4(bT;`@)=eQ|I zV7hOdQ?f4fS*EMt?a~Vq{mt7bG#mD$DJ_dR{`3loQH*8x$qZ$uftDcdJ1l|+2}t4i zt-EfgmNFji*4?{W=g%jYIdr$Iz)VI4$^}TAJ z?rVBA_SL?;>x1`N?6P~c2`8g2^fmJC+o#>?HWBL5e0k|gjhu^)l*;ND^`N~rEr;(~ zAlA%W5$cn}CHx8Pn8vv1=pDa4ho02Wa`1ok>eVALYd#9Yt`cF}AM&Z}EG*H~Yk3Oa zzC92ia&hzw$*WHNU%%i+=^k_L(o?;uVyCtcr{#nADVE9in4r-dXW9_W09xTl2KYyn05}&dntq zBR^76MNkkVVrT15jUz4Y?s6A8fIJ>CwSE6+UsGLsqj{K%Lb%6lrq2Dg0|DFj-DVRl zR$k^$w&0`fDvFgz8dVdVbB4o#hjcT}TJT&^R4WSDHiif@Ju`Q&6qyL|){^7enCq6^ z5H583R?Q{sED_VfHK}=4b$ck4zOu7t?jk@+l$TMm%uwciH>oQt-)^9%p%GSbr>JFL zuoiatq54?T>9f?e_YDm?$k=<=9*CHVdPU17QrNpaRBG4>>z|>tjGB(FCQRD3bQUNg zz8w*g^!Dn?keP@&%a%7T?b@%-HOGfVUivevwe8mYlk40U-VQ=QUJ>v6o3kBzYIjot zva_=viCA!Txd;1`fK8kH=%EYnR28KXGUMq<6(Wj2H?#0XGK%Ptp^Oi-+GGTVZOcT- zz!T@$pFi)HmzP&lUlh1~-Nubp{`gV-^7N4q(V{?|fH2-nRGjGJ zPY-ID9KO3LrQ4~q;=BL2Tm976WFt9Lsn2Gc$n*F`e%<=F_Ob^&xM@)vA8glFxP@YN z<)*`2^^H;N#~MWTHcF=5ua^?*xFctTAJN)j9hfJM0?7wHotfJMcwy(@kj9qnK9i*> z>mnqlBzErWjv@(G?#O*PIXN8SiIz377Nrjb*+ebxaq|iasv5fgiPYI+Hu&u=oAkvr zyN=H@ic^te!MW4JN6H=wzPF4&_4W#DixVOQsb*-cNBDew8uwESW+9`d@=Oz=mFuZZ z5T2rJGZqT`XzbGY2v{nWosn@!afa~Yn z?wJ|hp>TH-!6}j2pUk_fV=U_uL-8ye7D;I`>Pp)$nSQbgx?d?af1~)_5)!pRfs4GO zvJ=}#Yr8Es|96tuQ$wejucr+U532#5u480;T3D#qoa@%q?%>xpwLOT@*2!saftnJ_ zZ)Bg+3&TueMJise?S9=Vb7Xb7e>iA*87%--=ssJnnlXytgIzk6o3bzcd0Cc~_UT-T zc6GYd3CF%h%?*3>DiZaxv9l!-^s}`B(yW`rc55f^x5@p}E;pextBkDm1*K3e#|FTh zgZES0)OtP*#k`sEld(O4<6}cZf=BA=d)($3iIf2_rt0HGV&$h$bmT*I+zAy_lD$*N z}EV6HkJoSGsQteW;3@Ywvr{APS%^Qj*8e z&=9-ms8wzJmwUYGr9;xLWYiHW?Q|ad);QcqQWjcwpJ(1=tDa%d~`*BA(VV_JwcUAJ!C>2cr9(y@q&;F-NG&hO7oO-+UL zwdH;Fy?tBb!5;lm_hI=Utiz)|4)@=0rIyQ)JsLOB;>us6EqwLHjT;6RySAmyeU==k zzh~kN7&Fk4b2>%af#eD`6m0BOWHF@O(LWvGJGX2(aNXz(5;5D}b6>X>od1@;B;BG) zfoA=#)I?<+bsgc{rU2fcefU_Kbexi%BB83v@ffA5tn3tGhQqXv>8<|Wqkmsl= z?t|MMzLkm%e{uFt$2N+stu33(rPoJ)e8KLm$#ruD5>LH-9G@!tgJ-nBtM7_>-(*MgK6|csfNa_Y**gNH+vZ5$d@)b#21q=7Pc~;cR=E!3L?O-n znVjs#%*JBzV(O#I=!wLEeXx;I2>>^rq$;Nd@@x$Do~;)U7Z)!AXgK;vgi4>eh#vKo?#aG)L+~#zP~$;R9qmF4>uXx z9p`2z@-#Ef>g0?!T3wuIcB*-Hh~`&$c&l=8{Tr8&tp$%RweqUJC@e2m0o1L|9>|Tu z{@G#E@`gZpZVP0yfQTO-eXI)owzNB9SgPP~HO~(-Xht93ax`fjS%z<2ZN1q0xAW$B z7Zj5GwQJU`i^P^HdjI}?_XnS-=H7@4iLBQpe zD_1n4j)4H<%`>$V-Ij$4Bp(~g+Y=}ZZ>A}n~xP`UJ zvfcU*_)aPUs&wHytg8pW0L&f`0oK)tkMkx1Xq1n>UCANkkQcP`M6BD?ctAw9(*T)E z-up6?&sA0GMn*;f@g;4`R<0}or@Fd=uJSgkuv+t0PR{+Z(}P!CW)Qv_DaId}>)5Vu zc`s0n=W&}Et7C9`0oEIRajbjtr?0F=g03iqVOAzE0#w%OofkDjvlC#7<=59K5mTp6 z6PWqr$rFvFp^*{Sh=He36wn$eY3ZQtDx0s}xX~mzU*M7-SpA#rR>TC|r2OdbPXxMC z4cxAx_4dkgb-gO&SrQom1fAKxL8;Q}fspaMChkO>c8al>tB6IVeBRt_wkFq2ZgEM; zp8U&8aqo~a(W@&N#F{9l6$08ygVnPy^u3g5;HC@*?!_g7eh5n|1Hf#y@Fjx>VZ1or zV6Ohy<5$p$v{P^YNk7-zxT(Z{>y3=F4bQ;Ab)`>$zKS|_Yor=RC^Cl3;6X@OP$rI4 zac?^s(FQtINq8v}g-;{;$+vH(5VI6ub&-O=V`spPABkGs&qa(QiSvDQYkFmqgyjgP z=4@$cY1gw%sxc3Ddja$ zz(X)9VrF<`L>(ebrNaQ!2||hAzI_Yitcv}&Ip$Icq7XTl@mHb09Js5Uy}fJ16sqUR zmGqmA15Q99h=D8-!P`=5*Vib@F6*vGsExs!*Gl(yS=|3j*&`&R20qBkU=tJ=gyrPlr&UN(T^WL#>jg!k+h+wrzbQjb=|1*-8C8sm*EK7_kKx9NlN#2 z3>6L>vD~Ad6|r{vu^rG4a&vR}bY4b$ZEjZ2;ej$mGz+L>Sk`U){7JM0Mk7xU_qdmR3Dvjoo=~Tj zl*y;NJZ~RS%J`uH!FRJS5=0kr;VmDZKp&qHSqVndzQ%Oj+)ID9COMryUvbhVClaJY z>b|r4%-9J^C1MhZ$CtSdN2dGL=02UHV8>4 z$`SGdIyKpSdF1lt%WQ(iA7mvi&ufH(cYY8m8~o)+5Lpjy>-yva&{&~josgIJ$}~gPN3g5UPXAfQ#AKXwd||X0 z&marY#rKN|T!mjI&?r3_W&JRH_Z*ay6NQ%KdX47q zBYGBeY$5|UwFR;ua_Jl>Q}UyUu`$smTt=`73C&~r?Z0>XM%g*PVme=;(mFt0q7a<4 zf_~HQ{B-c7``kIRlRX#z{CW_sc$Wu))YNE}JrYgLEC4nkake*a`h1;ntVs6jdt7rQvx$(%HW6k0Z}B0FQ6k@x!tO%4W^b^iO6 zGEvlPO*{yQ!xoCxcDJ)ocCo!ub!E?g+drbiwRNlbA~nOEIobD-8}91A!Qn2@1aKAL z>s!9n@FXZbMGZPaSqe1hPG|vIJy;PV$H_u$?QN73iF&H1PCXGfczSR-1g8D$5)J~0 zKgk!MozUyYdZJDkxO{wU)tZ|F&3QM4AY@WT;yQ}MW#_ia{u^CX{XfY@d-=MJ!j_<$ zu2i@AqtAvqAO74k;}3S9G!vbJP#fF_xrWrtfC#{*hd)V*Lu`rIw<{-Tr@Z5%{Hjus z)zsF0xM|a-(Y{x$vHLIo6A%IUDHb}B#KqC*i{rf(i43%~mpZAp|2x}?tn)?E{~oq`rf4Mwz$Lg-CNm0~3z z3UV<}`t(S7PoRnnWdbd|#n=80MKr27eIWP*HjGb9oB-ji%sGJ&`qkFPO_4bN&GYVN zX+8=;CJw&`jVJ*=K0b{Z);lSaV0X-HY^F;y^2g#P89g;|QA0lq zn&O@8?W+K&ZGtrZZGCx)EbhSS)*~OZcindw2og3w=GgzW0cr((z_f-Rw!Z%6&6@+_ z10`=U^9K9~D=G*~dO+|{Q+&9rM=n&t8sP^A?f}{SZMhW~6f1GrfO{dKIbY47`TOxw%rAogQHn&ObVnb>8K7f2||xSNh=);qo=3uZpq31beA2Aht(^~gs4;U_WK+? z^9U4OWFw*?f`9h4$hvO#`8J7ZV``>Eo}avE+5o~Fva zT-rPl#jv3YO_yqXDx~VYP%L&i`V1Fe^v}1VsQhYvJG(Bd2M?5xjbdj7rm&%k({i9I zjTinTJGAM!!W}grj)vBkr+wW2{MtYXc>er3y1qLo1m|fb>RBY7OfkOJ4y_u}=_3=& z`UwpUjq713ic-y}nL%CNoHJ7sb(1Lg!4Z<2pTi?DU_J9<*NwjJ!^6@1IXBL*St=UY%WCMy$98RS zs&&vsfiH80i+8p=Blniti3AYEnoMdhKagSfGDeh*9Ohlx$1x@4_i`|0B>$Bdr*`Jfv_X*2q;DUP`O~)6 zZLIi4n)F{UK+TEb!0o>IoG(ipV9;uQV4+9eJjKFls|*Y}ooEnzSBZ@5q4Fa+N5F+DQg=HAo zkT#}aUT$|?lFh(zB!~4v4xJSa+pa2uZ4cy3w3yt)w!@3F2ZftJSkL$f)1rV|5K|D? zdiwf(?AWCHv&cq5Ts-(_>~F;4d#M>@bPU6n{ZzOx3okR`wit1fx?i&oe7?xr;~mmn zEq1;pRLoAkFm7okyu^N0x zr)2+w%Zhl+UJBZwdJu|)+qW^y7E-D=ivLjCl?5X};X6{k=dZFJ(hO-lg2lvmprwK- zsot6N<{8+eB|4Xczh`CuOOd{P+2&)%j!mLfF@`iHTU4J-{UpuSd6UM1{fYl%_lG4e$<+a9idKXU|tk8 ztb^$3VrC%h51;)PKCwT`kmu7|0(|lEj50(N^QeTy1NvHE!is~1qsSi-0RF2MLT!+_ zD5Pn(*P?X1KX$yg;koX#zF&ZDO6jCe`d7DD^FW)e1FcG#$~s ziAFY`ga)YjOrCnCLw4>9;#6_j!kCUIxXVVuLqgJ3i2lL2^qNm zIqiC5VR}6^PI5yB~NN5&!jOud*f|@nJ$s`Xi1g+=cw~N!cKY$rx zk)X+^Xf&QDAz*4IpE|Hx=cPP^hQE7-lji#(6?=kEjzwFU0AubL1k2=Tl?qy32LE0- z?Z@IrXWtqd8;d}ps)^M+a)W_G3ke-M)-g<}kNkp_$#d83#X0=FvN78!3EYx&Y3+3`1ADDuh~v2D5jNdMS($Zod}&SJ_Ftrs~&YXM{Xfv z_qXpju-H|Y-9l`0h1GwqfB{Y!8xfXK)=f+Hw&&7|v%!d77zHk4)(4F_afClh2 z5#>d#YSWy~EDWX4RHnsXahLjq_BEs)MqBR-!V!Qnf=km}vfvB;O=|ak@>_ ziF_+;cAHd~Z9F`&*xLk|V^diUR4iP5ki~Y9Z#Pt+nAJoc*+3)~?f3$c1b$2x!P*l80W*lCDBLP`X1Bs~O zJJEK$aCcrTg7y*c!2Gj4dCZqVFnw4;+#IK0>dcJ{Rs*S$IMX;cYG+?aXt^|U^xF07 z#U&+2U};c=UbcD4Z7ma%1}F@~o#~WT8mh1eo}-V>ps|BXkjJcy^SYX|6^Th0aI>Uk z3zhHL&yU5&>6d^89)hxhAhT@BNB|igt31L_Bz_fcM((az)X>7a&@Idc=3|Jnc@YEq zNoywPYGP4eISji*UU$zuUXofA(!7I0i3H8VV?GRJeOACaw!}5Ucteh)E&>9pJ`oi_t`- zvfwv;JEKZk{g}vfC+&rg zI!^{YQC^4-75~o8GdW|mC&@bD<3ux`87koTi*mmCqryJ_`(Ym*rWzDMuQrqfB^bk>KYzL){nwF()IjpWIQ%~1;%gVDBl$T@3B*}o z-I%5dAqL1O3W+LUFVx=Vs<|J!%|V3y7w;5jdY+EQsF( zDT;~}D>*JbIbrCg2`_1PV|pCi7khyS8e5(&K3fR*70=%Ruz20L(KA+OSOPR)g&3V{vGf)j&J`jlna$%YN`Xj zib8;BCK>2MBj)^fC*A(fRS849vsqdfioO>7Q4&u5@dOE>pr`)L%fDBOJN0i`jEcf& z^lUMTqu5x1&;n)VrtNd4`m?d={~h+6Kw`hk;>2)ny>j(xO_rk-QkGs=SQs?cOf0G8 z-;f(*I7CWBm>+@-T?n#vFk=!>2M;Fk%p@W?Xg~pnOg37)GpSy%@isLBLtS&W(>4ke z@%sS6QBhG`TwJ{b7X;g&?N5*??3;=MeJ9b=pIE2;Lk3)0E~wvnb3VbZX{ki0@P^&C0570~DvVKjsoSc9&VP+A?DXBvrm;>4_m zT~UL_iRRD!eQ;`Gpw4s2QW4u9A9jVF_0xAlV>2KEen&nbAt8O&Y0w0+OSO^=LW7@1 zQXq42Tfm~Znwq+3&>cOe0B)#G2Z8QI3qS}GUbVWPM96KY%;WGdu6y1P(*;9-3c;tg zHP7v=YLgv&rM=5+3i^eLR7NQ?8gIZxRlOV%4u#!1Zf7fRA<~F~4Y; zSLOU<2vp2B$-u@*)dy@ts(R#RZf>5ckNb?=C__*ElHC%s0LY>bW%uF99__Pz1_Zp7 zLIUcafBxxZ-HgXUs2xNCug2s2f)f;(#(=|Zl+l~B;RA~PSP6gL!xLtO-JHFZCxC zRwUu~6Z7fAl%5p8Z-PXn!=jeXzMoav!^5LMe09UaLIqeAbmb!vBE?0#zdW*t4HXs( zFqA^nHM3b{G2KkNNQe?>=JS!%C+51Xx#NJVVkI^cJT-BUA)2Ox+Mr07XN0@7vqDqv z0+YCP^QIrPyRTor#@8N}moF?TqF|nnqa=_ufLs#;k+Az~W~wGFgx@+$mc!JzH9B^> zknmMRa}lmD_HnSYCv7y9u`c1m4pgVB}X$+J*A}#~FMH z_c#_N6@!$6=H3A`aFuMs;h`l3(JT)|gikju8scahYUWtU2vm*Kfws2M{BqYAq~qgf z&&FfWq}dO(9xY~NNb0c$Iaw$>3AHO%uIz#23!y>lS8-4R)4jRR0<=(b$b{iOdh;GxCqG_Vb z-i9Tup*Q>W>xWhYUo%Z0A+QGAMo6(;H)6p!uLFK(%0SEbIK{kMx7yECd)NA{J9ZRq z%5xririyJ8$HL7DIlpnX3$G9pa0 zb+bg9iYJ%F!BSi| zo69Z&ZI}+=v_I4DKWbxpF%RPPqZbe549=ZQ)xnfo1DDic#4l7y}y|6d^}pNluhnY^6z7U}d(N0{qpo?~$Rm|*63 z4c5Z(c6+mQW4CZT_jBwxEfar#e~XK<`-&7&GRrTUyV)* z9pySKIyf^!iXH7d6!QH709|^)pX-pCv_Cl&aLd>C0XKZklq|#NQt%<^38Nh!(sN;; zB>~#>k*v7~&JX909Xp(9T8bO?>;YE`xvZ3%47aXleB`}=u= z4Wc4qDpHJeco1k!diF>eM0Ak8I4V%`3j&=h>#d*Y zH(AaS^bE8}eAjV9II)nLbD@t2WrdcrXaW$k-3#Sl9uWfXJagJVba8HGLR}9nyvUber|LNx|L7i~2-CLpvsJ*mEFvDiP~@YFq`C zZ*S|Rs_slAt8@0v$wu#)Sy?T{fh%Kih$48#tn5(?`VBFkMxrMt29h8+zO{@e;PhP*2Lpm9Gx1j2~d+?@sK zfVEs^D!!&3&b3n`@o-)8-aj+%2Zfc$)n2OW;Y>slbQ{@0mu;-XbSW+iuXEh3W~SA4SMrnk2s z4k!Xp+<}8eJLoFqB`F6?yol%a8HmKeKU@Q+$4EtldT#U?U49mT`)4&BjS=QYW_9+t zOv4K=QXv4>PZEdOPGhEy3v->B2L#I1iQFI0q|K z`&Sgzg!X_I+4lmsVNQ#1K5E(8qr`XT-pyOdQtR7jbsHnu{y*%QBEMEd2UGMfe zD#DbdJl;Lt z*R*=ostV%ifOUa%(gFL@Cnu;Ij{L`7Z=FH+-p`1Iq(PL#IP__)zP`34y*5p1UwDY5 zzC7eGg?o+2&J7;@nH{AW5c%P-*}d|{lq@}n9FmP`7$dt*Z$Kb_lege0I-vE)aaDl!BqVEWgzpiq)Omp`i=r`Mn zx*dGc-QNLcfmthl3#WC2ry%ADC1nB^T-bL5g99FjPJg?~a1U># zlCu{%z-+vUWoL;SU*c^Nyxv+-EmFO0^T+A(t4fMmP^SI#XHaU)vW?zfXKf_MR?Ju* zpn6)NI~!mc)TRp6aAf6NQORq9Tc$62kOMyi$|LUJ4Uak&s@CxG^sjHlT-b{EfpSWhTXQGKQcksctaEi8RwtdEOvA z4qS-<<#p&F68oZNk(j9pav0neued2VuVq;o;axKgy>ax@Mw?C)Ifk!WU0Bz<^5Qrk zjC={7hTDovGD1YH%mSNCq3_a0~Fq8zrec03!U+hpKqVV*WFnUGPHlAdvn-O8~s>w*T4zvr`qhcxn+-+NZQ zPF~)2IWx0q*#N_hk*!xG&+qRqcl=c>-XSgSLLVZSSw3?Af$XR_$AuQ?&b9Na(?eouHAIx~QhcghtYmuM8(~>Toql!=Gn)d3otJM~(9xp&DyH?7`%iq-U)N zN0LKrPp*++(-*IsH=_kN$y{Oq#eD5PBZ0m_vfI>!(7QULKPu0Nyo2y5pscLyHHOZN z5gfn1(h5hM^^MP-)w4O-JXmmbi_gk}p6fCqY;-tEH(B3tson+0DxSXWbId-j2ZR!{ z`NYN*ndq?PtWj#Ni=d0?GYbe0pDXNmnUQh*^5rFbe0-Z--gKxM7~K8(RnMros3@jI z#?i{ESU|D)E_ZtOtTHB0w84Ju{2ZxP{SXn9mzO{Kq+ewBr%#_&ty<-r_>)Lg9Y=ql zH2s9%WnC>D9o-OgTk0Oi*8CdFbh^!{{o_}z{1cjz)huHvS{*hC5_~Y^9F>H1#>SGX zC#+=RZn&}Eym^!A8zc#S7=_QzOgh4+yH#8~_<*0-!MGYOK0YOFkMp-4qQ$wo$H2e< z;{9%R7owE;xF6G(w#n^pXaW%7)ta@7^V!E?K{6-+3ySC7ECFFsnN{ zj;Z$NB?u=KoX0eg^d;lcl=&n&iUEM3yyW(iLT|(}p>USD0 zEG%5}i5&G@`{=x*<2qfHx;`eg6U}kc-5Ks-=w5u58ca9){MZ{}_HzK2cNws>Q|WvtQ3rs3tG4$ERdajN~7E=j>U!FSfl&hCox z1zE}18cRkNmYcD$d`2KPTH52|SDRewXRV8XM%!Q?J{%X{P~~-eq7veYb3Q_wHcm&h=5s!NZ%( zCtx3#_WA|uTDR9}&`Vnw!UT(P|Mjua(W^ij-l1c@42o5BjpZdAG=41flrDDTikKZ>|&$iy22`WTZp^FF$_) zjz-ga%X2w+u)?)ap~<~<>r!lp4dZ#J)SpN9mH)JD{V6-srSfhVKB40p8r;NGW)PK# zvXrfgqOg0WBY0uMCK$7j?CB4g`Kb2z;9x~??k|@bI>+jZed%@G){tL9J_p^$d?;WC zeeda^*|~EkIXS>`GS!TZiW9zn^KO}AK}d)XSn~Jx46+}99~sxI87wWAH2$#4=nphaFCQNo z)DOW^`JU?q)Ado`uKmJ6YFc&)W{;U3!z~X=hG4sp9kNwZSO4DMe;0(A0lx71*S60E z#&K#+3nWxc-41{sWGL8kw2# z^crR-fl3{7cEwjKtfHoVD>?AyDl%)2!&}$Qj(G(*@Uj9eg4K9r7(BkgndgiXFW0&Z z;l07Jjce!`Q-Ph-QUAnWKk=BGy@SEUxF+IQY{H<#*Ya`(D4bkcm?gZbGX&?e$W5gq zM;u!QAMdj@&T&I?i0#tZzBj$TLhjSfEUc{5Jxt!qutjaow*pPmsK24g2ix_#fB!oA z+pC(e-Mu_Lsdi~6Q+Z4e-AJB+a3BYRN%Ce`)rIpW@$5IyQd`vnej^|t5Pd?f`8-9R zA!F9P;(3dgM|E9H|HdgmsrL|g&qJ#?EVF@;F?~1cbZ2XxEF5BVK<1<(!#=k*dlwU> z+3)g=8!Mr5cK40UOtjLJ1P2HI?#~`b#!41!c10I~fqkRQrF{k-Gmb_xU;+E=+i7w9 zak|h?UJg?5Sm6*3bkF$z1V>JMl>lx1H%tv)W9SMYlWBMKj78Yl*(JjW91#^o(}bE1tIM!{sJ+%OhG|GqDt5x%Yk~QR(wA6WUsn+ zJUl$wVClkjgUNGFn~($ieXY(kvQaV6@hxAr>>IzwAD`r~@NjZ`lv7kxb9=Jf{Hn^A zEg&a_G(5u7I~np^7K6n_StllItncVIC9+k7I!zsLl-y(O-Mcq_EpKjS@9OG0 zf8j#nULJo%0h}b}=HdD0wQT6o-H6&y25HZ!P+2uKHLv^|xw$eR>YTS_DIIsRPCTsr zH83z&QJ@&9<^W;A{A6>Idh=;25|Sy7JzAmpwCCq8SzB9Q8@n$vAi>BeN_R)$>QlKJ zL`q{3wPX$m2>90B&38eE``O{6jOxUXQjbH%#{@F8nvYpHM#Z}xw|4T+B9;pXg=`SJ zsvBgG?F(x4PoVT}){$$jI3)LWJF0+D18hXvvxDy$Qos){>h~)jJ?fZcU)`s0;sn5= z04#-})(~#$lZ}?H-=#g6Ty^=ugA+L;zz)}xA}fPer_^E#`UeDD!LczB=Qj|g$QKfr zKa!8pxP_Ev1S%zwboKI-dUZ9VtDU#++~Lsed5$MXmiY#gbA^la&cLFIC>0K>iKs6P znfB&aw{SyoA*&07R6aWG2-_}edwcs>Mv3Xm6&{IWV`JBTL9nUY=;Ywwg##&{GthJW zj*P4T9mOF-cGv4;3oCk5Y;>VY_h@e6pWCg2> zv#aY~mWXqfqN1XTDk=rAscZ=>`qtN%u$D8bU32Qy+v;kKs5q_#Xl?c0DHnx}O|^Ls zJFwu|6efMQ$x+6{{by+%uX1BIp0Pc!=9{}YGg5I%3DUT~#ed-A*F2>efbVPaT#T7Q zOd(ov*K%^CAu_HY3q{XL_ob>z4rTBQX3Q)$`E*5H-C?kh3LLnJa*vniI)E(J<0$JA zP%s9$J0?4`0hMCMj?S3PCdS5B^7HefE-IT;;Tn*I_nk&#g}g*xY`T76e#pkgTsT&O zhdYIzE{GpB!^t?ml3&r$(Pxr>i6D%Q9LLf?c3Oj3!WiEotqtK=>P`Li>1)i)%wAvm zBgD6Jr_rfXgYu!o5*)#v07E)-oR|Kyf zrjRe-==7^(K`Y@FAmVyVwaWBEcrR{q$mV{r#555IrWGapo)e*cCqBVzE9jI#XFd&* z{y8-B=5vQd6%Pvw%PCB|GY-Rj*yE$i5~DF$!K?B?04JHF+)L5x4C9NgxCcVdy-T*N zPELY#AE8*^o1W*)7s3Od{H@*07Ai|;1?(Q zcU#f{_#!PmtKGja+60Cu?=1`Sq%{C6G&nIqHpmxP)X|m`UIn(X@UmV%zjXLRbu7D- z^BUMDUpsU$p@WT1(kk@2QcC78L;k}=_wQ#d`@Uwbg%Bi%R0LPO56b4-%1X7~mx~K> z^X7+p?*&#ZK9Ul8qVmqp`-+Q;2WwB-Y!MP-0=+eU0Cc9@P||4+)VXC;q+ZMX{aeW%I}uM~V^@Rdf8@`b{wG-ZI*9f6^g08ekiVaPw*JOqba7b@VXy*#Odmdc$gi$u z<_lWAWy_ZT47r+X9&J6-!94*-XaW60LsC+Pw$^c^`)b9ln@Yn7qy4c5wn#~BqEINw zDJciep4|l+fgSL7nxa3>!)$q2pthtO!G3zSp7?23(bEG$tbl1c1$6m!cDB!dpZ>-6 z3ronnS!-UnAV%!p=zu+qk5}%syLnUhF<>!_L0f?Q!Eh9h9Wz@49KZ1D6hs;rArta! z!*wuWqJmyvl~;+6h*(CJNM3%~S!?T|DA^fmpeY3k#k)Qd(#@W|dpF?h-#*7~W+eAy zn^qZQOa z2pTWLHwayWzJE(!h*33A(rr=%A#XeMi=o;4Z z<&bg~KwVzL#@48~j?p^`4G?sodFVIo^Tg~=1GT(MJB;q>#uqB#^k@h}A6-QTa_(GW z;kvbqqPdVzwh9QWfrE`j!eIy8GRtXbX#V?@j`NFTc0yNo^*48#-{w!FqHdtOKnt{V z08oi7Rpi-voUL6l@MeVm$B!RG(m{uoAG3KCvJ-%q0Q}Yfanxw@Yrj6f1>an-^Fool zeEII(yXkQF^euYs0yutvelt6qegEA9S`;1oTE1Wtt^!H+1{l>|N}2rb(BNR!Pre+!=wUsNkEcbu|9FhX&AWF$;rRDu zbV=pv_ww>m!)kaPm*8gdzNxvEQMwVVi*fz>>rfVqQCMLxWFH+H`}m(dT7zAa&Gp4H zT{ne>Y#lil7jY7qK)+~Bw{>*Tm|zayqs2l>(3>|>m+)11&=^)gG{iYW-@}_vpwPmo z^ibM0V-2?pDWKT0qQ!sKh>8M1fSAZm*pd)+8Zdxv6Vfzo{uVNh=Rg0elC(JSXgI z^Tlb{(zjsx&^P*Ga+Q+`82p=pIRCTuiad`w1@XIxyMqT04#F~F3~)`=zw+qg&`?`6 zp#i-A!M75gcX0Rs&`A;+4laolL-ds1c}HPsrruq&SB!7~|2O)VWt@sTs}uDlNAdM) zy+Ww$&7khPE>JJjiSlbzAJ#B_Q7E=aF5p?LES47Y`?;XfG96HL!#|v?tgP=IhJ|fL(z!;Z2rF>-QxehNbhGv*dT6f<>yyn5f&7LA$(PvojAGv$&*bT7Zc%XKFAmJ zEGvr*ZH2dZ(r>?hjlGH5FYgHX(AmZ1ZAl3Y6ovu-p=+lUb#>XGmoY+lfE5M0v)t3; zoT!M<4~-ujljrvXNg|6+<%zP)ga*{wOfE|cST2n$EpK5@iWLuGJCeox0eQf@bFq}& zY-A?rSn)iJS~!xsmhH|8s53arzy1^CSL{Q2#1*)ySob|9U?Z@mw>Y&U059IdM~_gU zyrYc(84IA53&O*w_r{sgGMx?opira1c|cj2)>McUM;HIOcJMNO@g2@J_rCOwUUzbV zuq~(3erZY_<@kIB>&A^+k-g9)DR+y9gkTJ143x{tYZ0NKByS)iZG4TyfLWD${)JOe zkTEDI=$$q=f>)Oz5W$nEs5(PSMhBe zD=;#X8$17oWGV?sOOrI+-6&-k2FA{F8^XaBNO!9|@hvt-KPY)C(t>0^6tiZ-)viMi z1sd8PsfMqTq{l=lDk;6gZu$1}=h8?uYD^T^uaCYMWBPF-q|5vkNwd32=>MP z*mXgt`W+ps&@!Q5TBxupGuj~IfCWDw*qyE96kZHQRhkC`I;w6wuA}3P^LsQ){D^E^ zT3^qCk_Y0$B5X$6_{xUgI8wekK>OrL6Exc%O1TIv)}M4;d6Pov_Hdzo|d1N~5W#cN3(AvUUIN8NN_f%;3cX>o#mK!4Ae6!C3VX9YQZbU>2`y*ADD?VDfwLy8yCk ziW-+C9k?_>l;BRAPoF-0)5qtkZi0e?gNTr@us?P*_UI-sfrA1c>gpc6UGq%rEZPYN z*O+42pq?5(kl(EgPWn2=m*mak1oh@5o$3vgP2sU%m^-(j){(jmw-!yZyi{mUr^9B zv{;OATnS3j`YT&tMV-!;tG-T@L0Ig>Bh+~D{hy_rtEkbmxPou7i`L+S&P1|8{!G{E zt5>c(Ilco#W{HW3Nqtij%}<8sz%Y<|ix@1}tU>Gl8^BPZiLtTzr;;+80vdXU-hkOer;Wn^xC1H1L$ z)8nUbDg}^mO|}DbSpg?&uvloL;PeIVcwVHXX1Mk%ALQbtB4k(~%p32l*4vMD1;Bt&VKN*P5+l!ok4DWc^6 zcpCTT`#b)Q`}ls3&wZo!`}KN0uj{%7j3JS6HPSne4bK{Vq$;cpAhw9gwPX3HvX z_c2dv{NgN_l6g zHP%m`K21FcO-4@Sfzz{W)1$|!FulZ6r+Oe_3P9b_L?Q|k6f<}tp3l3t?eAHCV{}Wz zwN@dImj7m*e+2WDWqzM@X*q?as?=+HCiPUGWnx(K0om1V*rY|!GdDI>sgq=-fhVU= z_ap+V_Uu8{x@zJH_yUV${{(SA0NHJD|aRWNHZI+Q<_{pqO+5hi?w$8HQuuL)}Vo#bp zxouNbr%PuC4<4M3Sc#qq$T>sa!1s+Op2B{xnARM?8yh}$CWL@h&=k! z{dUeb`ZQ^rMOp|e0v%fZOB-GC4pF^_F2S920aS@Tg$wOJSQ~{5UWd+-JIWwL07x38 zA*s#ha4=U|KNG7y^@MV!Xug`_ZNL}aZ#kfm#>eZ_kNygJM64GUqXxd!8 zI@qP5D)Y^w2qoSqFc9_02+xkDgXUgd)EorSQi3XY2qPf__G*S^%rGH+xr63U#vNR~f6ZB-`}Y60 z)g_8eb#<)1-}12&AHmFB+D#uacskBi!zTAl4q~bt=ldXB(k>T1m&SCmAQ*} z%a-8VA>vhJ@a4<8NS8!8mYr?K)iK6xAb0Z=vlFD^{*`;*_qU-anFBZ5QidF~f$phLOT4)rSt2Qu5Dbi3=*f^ngpFXV?ya&btrbEm%xU4p`N&ok8YvKz!dHB5PG(X9$8&kb}Kz-09C)wjN z0`681lSI+kyZppl_0U(U|I1xmS#T9E`~RQ2fb}AdPw;mKi}O6M$zt~?dY)2(nmd%+ z&BHQ=w`Oq0Oh0l~j{yUw7Ob|n_ra9{XeN>XAy|FZZu~N__v`jQ4CD`_*G54nGXjG#EC=^^nQ&qB9>YR@+M#Eb$CtbCs``;*&w{w8t z2t%dw^Ycpxfd-P77#O4;1UWGADNE6TiwMRD`Xa)-G40u|B^R>v?OR{L-hd|CZ&xFW zP@ics5}`4_*Cjv_#fm80P5LZvi#gnO#H_6(mB<-H{8686C@-qUsZ*grXrQDj-&Fhi zQQBUc`x}A&I03W5&}j=G9x;rFa#&}{vSq%A{d(|5$T1#tiGd((^R6KH?SkZb2TF(% z$Yt7dUBG+rMdCt1W@IfMC+sd-L?rOUP&bmr1D4J#|s-{3!-t`o?Pn`OWF~-}7un6>NHBKhT#) z0T6}43^{vtg7SNKeg#QYb@g@{KtOr*}XA(>V zcE_dZ2oG|Iz^u$no{Ep}ibh%sQ#H-R-t8vOo!f~(Lb_z4Y8M6xEp1_VxZ`9U53YC; z>H5#Fo_`}@Lf!J^%LQoxeF6!^V1cadj~_q&1;VtnQsR;bg!%16c|=w{ICxn*%A+V$ z3gjrXOj4Xe4%ICRU`}Vh`MxhGlH3$bv^{w7Y813YE%ArYxTl=>xMUWI15yvPE&ePW zI>ih$*1Z~vs%mOpe)|XJeLBBS>op6v+(3@!{9->HyG^A1w#>S3dY@0A7d{5@g znd2j#{I$h2sFa7T?kY$r&M{D-)$BJXhOcePJxpd^BNyM!QYlM%!fxYCA|D7Qj~IzK zYkatQ8I8>CNSX@luC;{Qg6Sh%X7HmC+-dnUz96&J3LvGmDCpl4%(sjh#K)Tfy#sJ= z!^itjc+KRshOv^8lFg4`f;ye5KOby@P~geSPo!@F|0lX3gcMrGr984apj8!IP};3q z&1F5C@(<G}dd@1pKcyqD8s&)9Z`p&u{itvHuSY{ar4ZYuq9P{>d#+i2wIfXIJPTMv3&B z6>*C=w>zMx|qOpbhc@`wx(BjYRX)Hp*z7EN>uG!B>o}R)iESj1)rFT z)(HWps4v>I@!GpLZ_t<*s72ReBP(%-$rVW(a1^UM-M4TL1+fi9H!0AQ{{*zMrnucO zS33~VI}c<$>;>wIg4Nd6?wlhM4~2S4M#hA6jemgSjnTfX*P=vAGrue-IM^0FtElaF z?`Ek*q7KK^i;N(?1GnVBfdlHZ$Uv)(8LDsNuDZCoUS8u_*1aOTgqOOKT{pK`@i{frdP00Yd$tTEX<6n!OoTvLb^~Jk&A_tXv5sd}qpuALr*=Gv!np^9xfC zVulg)Ft@5WFw98Xhd#W2*AeZwtmELL+bSuwSg~To<(%c$u3ARsDo%==RnB!uJ?QD# z9DL?+aU3d`-w*81gj5z1si(Tfi}CV{%n27S#z z8o7*$dRS)>X8%vhLc_%!{F}1w=`tMTgAji3rUn`fGwE237&}io=l#8I%elPE-gU35!@P{iEagLyC!{R^+PLV%aar_jaZukObWlppVXcYlYQ zE$2xIU?UaO^W6FKv{KrOG><5*1h7Az4|Yo{;ua~gJBeISSR}j9P<5LNTuhNBHG-f` zcW@?uzw$phxhV6VYEL@6eKj@5vw(pN=21^?UkK%T!q%lvk2<0@{WKF2wyckXz`Kw%1iIH?(;R0J1FSoj{ zw>%yisd&ZHiAC=|$)8Ml5;5Iz|Lw(s#ag&u@7?2EJ-RxgLIt!@Gl=KceavQ`hHlGa zyEpv2DH=wP5zvQ7O(J5Aa8>}i%W?5K-oIELENIMf&Ky*DB z9BNOc{h+0De!?T^aqryRUzh>SVQVJ5zGk{kvtPe$ly?+Ch?+c(fP?RC{&=^ruruG( z``EE#4lhvgD1EA3QFL##KyUalcwFXn5vU;%lQ9z~FC3pTd2-7gs*#hJqb}(6Pn>b~ z@r+qNm;g_QNvmeOOsVDcq}{&Vl2K(^(VIVgcDAKV5Gwk!TSs65rE?axm0EfH zpIrMfE8Nt1%a$Hv#w?(#*4YS{0Yj6E9OSY|NXLxaT!qX4m94Kbh2c6ZPYSw=(hnb= z`vi?Sf~;eHqD!Y>ZL7yEod>VCnlncxa#sD6`_P&1J-ebsQ7JS!6;cuRtozr(uck$# z-(586xi9RUMz!_Ey@gMrTRRPOeqK$l<-O+;BCqGK>7xhG2s-94Y5X^O3y{lR$Br%7 z+4|Q)%1}ylvLbzs+?L1XyAD_Q1M-iq_O%>9gB+>0$%lb&)c$rl1%zB6`zKH&SZ8bY zlG`!34?HqKg`RAWv13(uDdE@WZ?Q5ptuoI%V0^~FKKb$ES#x4|w%fY}yqhDk@}x5l zdXM~)VOrmNvx)h_g^gMFG_QTbVQd28wFLM3oD)&9b2iI;Pdub<=Yb<)Yu8j=UTc_> z{b|Av@sN%lM=SMUcz8d0pd4CJY;rdS&+W!l(~cvKmeO~;@8nMfK)u)kpEd&r2ZtUO zv#f|~%+b|k%`-L4Yp()Zd1+y;_?UH-A54d}Z@<6elLUj_`}KRT==7^~1OZ~$u4&`1 zBT!d6IkU?HA<-it?gJ*EdCx7{nKV=?5F{zTq zU&BPLN@)uoOl2lz?z=w{8A$ErE06X*yBF9~PTIKvlu4MkDwl$#!FRXak|ojzf`$(t zE`%E+^#fW+sc`Xih7DV@cFp?hy}Z1<>|Z2~p)>PqO28$W2{tw%)5g8zDAgMD5P4~2 z1_m1;=gz&k9Jw{}!UfoxW)x$n6vB(|78f^$yKO)cfHF->R1Fy!@8;XRDk*WNo`$y* zwEHb5Z9eDn$o%C_r@FotqEk5UMlAZpV2tb8lOMUgd-m_&ap6M$#Y>mA`o=3k%k-eV z(}h9APy-1yn?cs8kT&gS&6+h}sKWEY+lvQMAEgx*{s>o@$G_B8HTx!pnQv^a)!?0Y zpovi(Hf(mE;SH)|#*7KsKZy~ll2@<1h#9GO@3y8{GyUh`T794@Gyv`Y)C~fM1BW=b z0M@8$*IZw{{>NIYFYi}cQO=zn*LDGJ1DxtaHM>)=t4IK0jknTW+c008g6e zjANCQlvEnlLwS~qhc_~t5%e>~j;rinLiE^I&LN@E^0VEczqc@o%i5Bi1I;J{DYuS| z_=G})G*0)kjg{4lj?bDNMTInEX1MvT4gI+rqQ@l8o}=SH+NAG4&NMR%ZC`V4%U0Iw zOq}+N$tO7_rC{$3+r+($j2y7zPUKOzG=xZ{@810=aQ#eKN3UgU^t?NKWRHu!PHCO5 zL9XQC#D2_u(no5ZbqUFPK>Z{glKe@t@bzcs4jei(~NpJpR}YRZ6Q(A)XTyBMFI?a+9SRVhsa33x_TvqHu0uyNy)*o2w~CQ(0ORprKF_ZynU;$zV{?*8i@n* zKQ*6UBo!w*jg7z5+9hA>W?YObE!(@>4Z$vk2y!8Ce zIFY{PudVnj2B3J8DY>~(ha&ncw?u$lSyST?7PfRpIS8hM!OUyj1aZBKH^@O!?bD|P zfHB`06-R5zWzTtFBc?m<$?v9cI-Y_`Ckh*bz~JDt0Ejk;M zc9(q_4qyUkjUJc?6}$j?Kwm;tDz3)p^RDyAf8X73YIa`nyVO>SqRW&*SA4yJ3WMXL zi0B>63Ls;4MoCfe?UZfiH(j`_^jE|_$$}@$-}dPWpqE;);{7W<#lLM)_0S2l&qiK* zx6zGB`fapVQJsqV0Dv+MSysYNWWoY{luEt9TtE;HE9IxubcF=;lvpgVjGSfv=opoi zM>M}27{u+0_s!B@#N?Ayb7Is1*Aq0bciX7*{N&f-YuI(=V zFsni}z_jIOb$X)P@eD}-j>zYhz(ZNjOxUn$Ww z>A?6fIDpnIgc>E@-u-W}?PKXVYsgfhUTe`I@ff>r|Ngb~={DEX84N*jZ}2AV*|RQW zhn4H5=1<{6P>+%9JSeSfwvg_HvsZhC+js7y(+*$DF=J&!Qwb-u^!4jL9^-|7=fWUp z@Kv*lDksvBM;2{<>HS2)&H9m@*}bO3p;xz3A{*MbQ$5$2TVc=E}_{IdSfUJ zUE0rNU?cyTWWnW*h+gPwxY^f@rzcD`Fdn8Dg2}&$l(c{p>a(Wg|KK}``%QXn-+PKg zVs2qkN(DL`Gxo}QnpI->Xs~jdPAE7TU``+1`rnCD*WdYGZr`zEyTp(gXrqABm2lt* zwqqQZlMY|1tIO86GmJdQ?L{%Yiwd$FO_8)j6c9|Xrh}EmxCm@{iTHVFT^re8C?!Gr zrh{84^H;wm1w)1?eiC1f!r4LP! z{?mpoL)+|0c4W*Nv0t&b*LeD(NZ^E8iH~$;#b3#^P}0`iQ>6k(;a?*WBbVIU#N>oR zhYlWaA7#9p3A{VQ^MO8xcao@KR}?ySlrCvhd?2)C9ZX@pMYoITzyJ)sx(n@ujEq96 z8U?mX`7xS&@eB*7{U;1Dva>s*^QyFT8{HTVyiM*&eYvd)*Ce!7pc)L3KvdyctcFG zDmn)taEC=iy7AJGFVDcO}q|H04w8>~}+cCS5^?@P1DcWq1x(JQMqD7$!ZG;6OYKNWRCSH~xtHkPIKlsqKmi@RL z8(`e2?(2B7d-m*6U3on^I+bw)K~?cie)HwM+K$owBckgue7G_=Y$C)U3{Knj?RRi+ ztx?Yv#5)fX8g2+`Tb$o0|J&VM`R|Tw)*mrq&g;Q*l?5oL&=S9yIA?VL zYcY36$BqHDD5Q`=Dnn?vh0wK(HPqjPS*LGL5+>jV$==V(c%sh zWXEUiaqTu>UtgoppKfkjYi^$SJfdjJ`vdFK>c4M#o>~6<{`aHn^u9gca{uS^b;YlL z_Uqql#`@Q`43IKQDq)x~x9Gdao^NOMcS!$hWUzs^46A%%kT%NeolF|o!2bxs2~oR{ z=%6if8g@v*AZwzSoPs14jo?qk39U}{Jrxud)(7R`b}l|~a{ArKo*w2y0k8m4b?TUJ zpI>DDC29rG6vTs=UgUSFy@{nMX=zeSWu8v#_ut2taqiP`Nyg`na+nx(!#}Ju+54cL>&Wh7 z-Q<|m68Dx2B&Gmiq^C7e^-#Emqh&In+JQ;}T67UTRH2cbGe;RstQS3f!NhH<{~8&0 z#8^h{rBv02r-NKTsOPMb^n|RJ8St9-Pvp@R3Bw5V9ZkXIPQ&&qm^EK!Z-0_Xz98DJ zl{lUFzEVB*fOMr@XM{?xZRgIi;pXQ*oo#0z)3STm(|=lkzu#t${EXN^I}m=Sz`awO z&%tFuqRJcnE4fZ={ILRqL34ZCmTIR%(SntU*+KIEhELCZsquuYMCj(hnw8M4qJLg= zx2K1KnbDZ7ja|u>?qFQDb@|X45X~U+i@2=Y>q z0SLKZ8?0R1kx4S&-IuLcVM|mI3K_HA68F6W2v-&RJgO{ zvTjg}7!#ffuB}iKtw>;8{&|b{uGfPU42m^r_N{z=qb+bzoNC(;Sx$nhkW^Rcs+5kLAg~Yel>V|ZCCR!?~4S4zqkhp4O~Vhk`fb)aF^B?G^071 zv9bOCF5x7_*~^#gL0>1TODxseirFugi`n3PF0Kk)qmU5Oi>6C>HrebT*AhZQAVn)i z6jQ_psi z#F`SFRfU7Eu6){#1h;&3r~jUqOn6yY;DmJmb1_^gMq;SCbl5O8+NDl`1;*XhJ2`1y z*~?FRORc>Y6_8u0HjKCsf1zawuLJGw;A-2ndhl5=;D>az}(pSE3t5iJQNanB0Tw`1CXBq=Q`9*`Pn`CitkiayNFeK6gz%ITDabe+7hBo*) zx%v6R8THYl{EYzR9Z;bthJ`L0ZhlYwG3UyXCYao{=1A~x=2kc@U9uzqOf)(%K| zyf5qPWH&drUe_)x!f#KSR44{K*=3wxbac8UjU$GT{J_NH#*dd`$b#3H-lG1gx{7v& zGD$nX@z;Vw%q>)w9(+?j{_kyhX&ZEOpVrtZceu_aC{t*J(Z?x+@8d$wm{_m3iLR6T z#fw@(bIKcV8rDLBxYdIfA|;uytMi#xkNajQV+zn0=Dr2dQRD(4K;xJQD@c)LSb=G3 z@(h8nKLb$=$2XjcKd0Z}VQ%j4(EOuj8EqI*55i;hXx=O+g@->jwtXaW5D(B4F7Lak zfU9lSOqmi<=sl9LGLuU_LxxoBY1%MHn_6nZWPj4H=gO{!Iy+h8RIlk z?r&;?dvjP(sY~edmiVn0{@oh)}w@FH3no=Bm>Q13A@$|g4rRY_rDwHvlw3yx{ zI*Dq4*@Pw%;Yt4LvBd?ZpvTXit;EmeJeY4z83flv7s3na&-(T2E76r%IGVgD5?uf; zi^QE(gNNsh=QRC=pV(HlM+i&D`bD27_kR?CXGLkFGWBdQg9;ESDyRg5x_>yz5#tP` zqPOedKH#d$cSlJw6HROBmSnH&{_p;pE$e^B|5l1Bd1nV54rN<<;~DgdO<7{*bnWww zZ&;&$c`JsVb`AKhQhK`=z;Q^7;bmaJdIr~tDj8It6|Y{uel4__4(ryS-QB29$nCi5!F?qa^OOS z5H1MSD7wQ_1NuxE ziLtA=Bj&4-f5EV}a1Xt6`u6SHL2*AtRautqEAk0A;%wCJ%9~~!z3k3) za3t+&Z}b@2Nf6NZ`JCU~+p*?n-C#bA82CbCvZ>}xTYPwYp}3ufMHp}SUfoM&)>57v z#Y{<>$Df<#aG8bCc~MOmSTzbK$;zn($HMoKL)_|iOlDIy{#49-kW zlKc2^297;B*T%?7t6|z$`VdQiaV*Ts1uw|nbU3hgZxiO!P&EiRH7C}wSL;?YrBh2@ zi%Fn)^Nx(Y#5ReMhs~EQ&b(0uQt7#wPU}r$`>D68zkO>V;n~hUw9@P|sO_!1)=T!lB7ILAHvnu772^7Kb5R!daIotEqw8N5g&*28?FS>PX#`$Ab8FQVQ_Pv@feFOUHwpxT7sV%{+<;zN>ca z+?hryuvxsg+3eX*%(P=FAe|Y90lY-T#AL8^ReHdHNV9LZ!9ETZ*@}!mN)uBAx+D@1 zl23+*x5Pu^&HMLXesF+N!7GLv%Nx-Rj9?u3|2 z;cu|U;)pqE{07FA#${JO?a}KYFP`XxuyQ+@Y7sIee*De2BenW_n|q61KNg4b2y%6> z-(luGJl0Ne{J~DybTcVwEG$8o38YShEnaWxkD$9`y3{;k*3`GrI3OD7>u*aP)wz|d ztOFDC^m9Ui_(C{E>$unK>3K0bFZH4J0kZ4>4BHojw2a30m~w2SVp2o(&eU1~1>ny4 zn+8;+H}K2_yq-FBs#}xj!F(qHdoY+1?-v<|>BY!_jCpZUa`W=^anltea-!=7A{ECA zyW@pr^+xB9!zn9KCZ~z9RQgY1y6(r1)WX8JJMZyj8jKFF5}{V`vf(|<@|U)i-T{j~ z?@R^f0gWWfXQY(7bU8)0;>=g0PPXy)bCkTRZ4PT~PY>;vfEw5t2Nk~>X{7j~4e5^M)VlG1p4}Qw-SL@79q%881*EP*>*0&_pRvue;zZXRF#vGgpO5(-!gy;V zNiZ6m9|K+0k^M;y3pkOXPIM!KYa?y^bz>NvPTb9R8-!gz-sXANmfzB{O6-6AXr=2@ zGK)4r&IX8J4Xik@e3-B>0W*t6-auROt5(HP}6_md#seff( z>_lM~Ox^TDx;#1=zBM8#iR4L-Ya$Nh+gr)?QThS0mO{Upsm=CP|(#QX_+|Ya2hq9 zzX&>`uJ?q`*zm2y_KMrj%|QWu1mlhoj_lYLehgX;l3d^q_a8In=a{5@0r$C{-xHra zc(91}#vz7xpBdFu0{2IexNwX5X2*9>YjjK(bmZQO4(h?PzLTy0)DwCM`TIxl zTF@ivX^Z-$o%p!lm^B{SV$a|_Wjnofgn;j9@mPFBA3 z3(bV`H7>et79I$5@Wn2$`N_Zuc`f@I1@J9=4$SN*ryhSWB3p0F#!pA>7gm+D&hTrh z=i$V3N4B!<2Ry_olq7*;_`!Wf?!A<~G$1gbf7GPBTdT}Y_fJuc_BK?vfiv#kv!_SG zrYeKd%@NCWvgmOeU8(?W`s-GtsHR#A5{qZYR)+T44>`3rx|Oay2@f3q{NckZ>8^C~ zG9iwXZL9m-p{bqnWagYXS&Swbeo@hL>AQS9PoyrMq&_Gku*D9+Nf`%>;Of{CQ_r|* zd8CNd?q?p0GfYTqzbYp=`DD7C*oal#rQx`#&ZOJf?c~%Ox}I|^y}-Y8d@(&V4t)8= zwHOI?hVsnLa_v}=@nFkF>g>FsjdXs^g1@ur$e9fEd62DbdAs*FaT@s%Pw{`u*tNG2 zUrAyWZl28^J@wgPn{<3`-rN%YtPAawH)V+qNe5~KyIk7>H;j`H97ROBeUR?U0# z;+t6KqBR^vqH)D%9n-0Ft*=B!FOrC@Q~5<*%_f|e-XWtxDRn0^(_1XV=#S1~^|5y{ z1I4a`P4(EkrvR3eZKv2I&#Ur=*xK@=rk~Yp9FvXfZJ=IVI#~qt^J}_YaZF(I-m`jw zTmK%n>h5D62!)))ny7fDO&;(&6_BBG=Am)hEj@Kh5=R&eO8vbEhoqs$rszEJsSvol&kXRw*X z{^8lyh(_w-`TMgYXAaMBf$J#w@Ifv^8Gpqt)C5QGzsJQvbTf!~Rah0?6S$~XOl+Mv z=Hzj5teF1D+ZY_*B}19%NL^Z92M-+z0pW>(IQkf;KAjB`+bUh+NSpSBSHrV&V(jyp zN`%qK!dXbMKvuKOF)g39zU!WD^VlQeL(661MLO4Tgnqj(A*d8WZ;3U%q)_v6VL}4t zlt>^71t>o;3_fe{%7Q&(1AKi2AMpJP*DIo7(wHNaWjZu| zCF#o8`+D0LleXYYLGt3)6#oHN#8B5e%4rlYhO3k@rvb9ReEhns%&hEd)-NO+RWH7A z$s=NioE``kvE>cCDY`jK%%d})K=&C1i`Eiy3%y3+m1X35yX>|8 zKj^kcezK$SW+}F?`Zuwr4ft-C35_(BvBzIbR=+v(uRI27Ie|J2TIv^w=(u zC^;T3#dI<66Qrrc;xCY995)tGj|YI^0)jQO<+K!|=M} z)8QWDk4t{#IGWCx(>Jb%BW#{ar*LzPVTQZtrj`t zq$>}}!@&{zIvEb1f5c(TE$?k_xvVEntf3k+a}A*>P4K>PWs~u zR|A!32J|^UuR-~ia{JaTm;}6^V{uz<(UK(@IUKR`HJ_%<^=kE$V$Cq-1zL-j5Bz@7 zyhH2Ivt3?M^ey@j6DQ^*40Q^*Voss?nj|jX%Fx3CMfA0zTX<|18>jpLdt$ z$L_lio>SD;J}&;CLFtNFfvm(mGSE)e*8egMD2=05qX+q1aG??5cxf4eahF75k@oDs zPA>tOE{#YtoMU}`TP6*%GF_tZG-@QN{qCVb-oekFJ^OM&J(ag3H_QL_uSEJ$JH5`f zUDENx!!UVm`PQu~DtHY`U^3b!1f)8}-MG>B`7cA=rw)*6gTLzp_8H_8?G3ZQDzJ8A zXU~}1sSgF-{b^D@gYGHbm!tAed%fU>gZ|*pF#KRvv>j0~RBgRxJG=koqQue8Kep=+Z4>jMr<(IHvvBkEHq$pX zHQc0jk?Z4_BRky^Z?BxYO2>V!ksbYYJ9h7WF9$OJHdMUvN~61KTb%R{%4hxbk!TRAn<|-cdiqGwL#A>wi={lX! z0%Dh@EdFBATDo8HFeT|YlEUlw`E}jdTW+}8iXB2b?uS|LiJoj?Qhs8*lgjM3rcT|1 z6c-CFDRC;^?|HE;ZFI8uDK8In17V!F)c0U5wM~Bpsv;NMJn$3qF~=lDFi)uy4=)-= zso3vGGhEydCOdEN&hD%H50_`v*CdU;bJ_rEMjc0*ai(!gN@ol(Kqc#Fm#Ws=<86c; zT3&g0b%C#+tr#Rie)DETs!#bgzH5@iwVHKYJV=ZJ~E9~IAfNc%lFwRzK~ z$`~g9#F&w!vg}qXL>gv;UHsKaJyMdod9=J)3kfiQmFs z;2NPImL$`OzKmn8WE_q4OT$(c=p3(Z0Nlqn2%i4NXOFkJkkj4zdsRtUy)5CG^fDQz(*Z$`s(4C)@^&toH4_lYJL$LwR%0?UwaG%6p=rG zG>kr7iUJ$i)oa({vb5<7lH86>XW`KN^>_9=|NJrJ#O{CqrPetz5>lH+LPyBl26ie5 zfsjC_h-elsX2qHi@}9TQgwNAhpa*ncZGW-M!!@hSPkwSZ(1bC;Dz|cI$co*U@E#w0 zR83;PVg;{%hsrvBmOn(7X3@nxV66Eso);7xoZjk}5>1Y(WkzYqxw$$XE(bl5n)ABb zwNBDtkC0MqG=D;v?MclTd^J$cRt{i#i!#{w`G(1vSr2F%Pr5i|Qv(uKO{Y48KY9i_ zq#DN4CVNkyvTh;)o?5J1r`IM`*Ky3~(SgS$rX5bJ$*D(SlYZl{7B-)qnNQIr~0|sg;#pr`@Y!tlDdu$s3`L_4Sr8mvSNa9`VJF>8= z?+}G%eSZuvHM}wQ{9)>a;QCQYUAxLj4zfqGFzJ`#Pn0>Xo*!+6!40Y_q&h+jAt~WY zL`Kza6>B;Tw=Jf&yK{WZ&HQl+5(<4O2_v;UGpSH#^3p`i7?~Ln!?Qbgub|)$jXP5- zDAGRHSHXz|Ei|FcRa#!2c4AFYT+sA-X0&M;y^WSv(PMIYqVG1<OMuO*d)>P7fR zjr|2yjQ!43q3kn@LdWdBvJW2T=9WB!dvUR>vsC;!amLrAZGqFiS`p@U*t6Zp13A;om#J-9sB171^*@Cpvad z`X7k(^*p3IcyT8Mv8U(NE0?Ywea6v1J9YIqH1_;Ml^#0=rta?w?}wd`YrT-mIc{v; zG#Mz77qe;}g=loXQ}AK}Tj>5*;=qg6p3s0!oTwRJIfwqK-m(4rPdOx{?sUJU*r5Yr zDXaB;DuBKgBRiQtO=MhAZxuF2^n6w6l%rD-qJ_Bmq|oo4_u&7;7$wbzS6_;Xii{48 zCdcRGUnFeJzc?k2a?gq&F3QGnjrZo8>0Z5dO?bk7C{E~d|HN3qpwJQS7nfzONb&1C zZDEUM&Emg|oVcs=tuU;L#qt*Z>gs4jT$Rg88?F8O&9|b)I-%vZNI11S)-tpM7ZX=` zU99d~?yN0_#N#4fkOhQs5Szubn@DAEUy_v>K_Wo~ExhZ5mIgtY7{=s?dH^CC8|&AY zdJQm(1O2$&Sym7gl6vxD*}W5E1Ddz$SoxY*D%5#`SEp!=z2h_xQ6skS{;3yCMC%#@ z0r{r=-g~A{cxDF$bx1co8l~OWe6-1a1zS1cV-<^4&(PJ+v+DPx+OC@X{+z7&caHl|AF(;(g$AhQV)U_wsu!g zaHmkIdLe70P<*p*PSwu8@++C|dwPbQ9{--rRw=9>5f)Cr#YXH0k9$^|!UDpHjO%VK z=AsWAux7=IoG`_r$@i7VGoP__H9#Yblp^A44|J!DGNhnJboP5ql_YjdGBE6E?+VL} z()U148}&Oq)pMQ;rR2gGI-Ge6O0qxQ=$P2u?&)L?^kqah7?DubGw{TVsDu>VqF-?X z9PQ}Um%dGCQkAHs#Yz}?8xhq|@XW0lqv7^Cd=GL11_uR$AxWl+HdNYAxnxx9Id_au zvEU0~`8JM^f3dn-;3r{-CG_|C~W`wvSU-HmT2&E+fAn%gZSkH}PW)EQ^z5F4p zma(?nfm;-3TEZaAPyJ7G$OFhgTOn4oXmoN1Z2;g)u=3r6v-Pp>af zYd?NS;EbkyJMSx@Xg{|wVdM#`2e|_W0t?0LUh8ENpZa37caAw{&Yo2tJJw38DKO8M&@Ai^FkRU=oROL%=w_?ht9Bpr=p}b_v&{f4183gr$QagCF)g zSvTt9o30)@nr{)=Y7QQy{2x))FG^>S7iLebetiA76A2C2b9~XNA17N*FF?2vf2TZK zc1Itazcq&a621MW<4`P}scg2BicIKR=~0yN_RA^=L9*97DJu5bjQhN*aUabt-Nz}P z6wu1@6_Om;&n4{_DhK%c2bxr22YO&-DpH|>odR~E%tXq9Jx zZ|bfx5$L;Yi)VdCN{YVL$>nr}d#$$Gl=+5nw>qO{WFNfWcfOOIejtgwh0M!XrGrd$ zBX7ipVKRw3)gxSoN()+M{pZEV2~S5KpJcxOSRZmysM<|bh$qjSslE3;AJH0odCCbW z#Us;M9q2pIkw#~g?P+t3iYD6(qId3=)D?x&TI4WR%oS=5R=H=rUj_ZY{_;k6{?V#N z>U*vE8lP)AdoD}aDc_`t1QDb8jiWjWmp4_O>7TsYr4VS~PDxXScS#+LD?0x$9RrKpP^#;^8$o^WYbl-8`;lt;3BDzUT9gaq;#r&5ar|XkjL#1b|pSX&p=TYpc z?yU8yTVO>qAN5o_s70fcu5{E6;+MQt4-(Yg-oAt|BnAfXl6?6o)TOGd`H5K_50+I_ z^olDHt7i2cUq#_A_M}KcLyW=y_rumXItCUiE`%e=n<3;NuhJfkc56`PxdhMi()B{l zrv_6WEEa2k_g&Y#oyVULdg8_g3f_ZI5L@-wGTtsYxb>H&9TK!kb6X*#ZF|go_G!Wd zR$cD%otY4MUUw_?=Li_iJcqUe(a#af*6Y@cL5sEnvj<9R9mt%{>aV)ta9ED~Bmc&{Ox!N8W)ko4n`U(wJ?v$V+I1Iv zmW}2f#;GuXEbF(u1p2tL;rlvvQym-S9J_1R-BI$_)LmSKjZpJP{XzFOXZuS+cb-ix z|3I06!S&aT%iDi<81Y9$fl5D}1Bd6}xoXcwf@2yA69hMK-iAS)+)inXV#s0aMFe*9 z0z=OA6r`7B!KKCi!i`ln*txM`gqY1hy{E6`Gh5lA|NAepJJN;M296FBuL9S(_&gBd ztzf=<<1%yvVmy?#Oe#`R0+z<*#3=bgNZDmCqIyxMU^FlM#M`**o!P{1``5*3Lj;Qp z5h5G>{=u16P}9v%+HVz-MY`S+zotinT0i-6kxA9;FzUTsJlY+)8B(1*4|ViiE<7g* z1_m={w#QgI#70}sfXsm-+pg>;yMx%1v0(lF$;)0FxYd6gMlL%vmi5l+;(s){5auN5 zuT@FieJm$VPH`lTy+XU1=QzFxy4^p~@r2*f@Jko2NksET@ZUmm!?Gf2?yy*Q^r$FN z-gv?UuQwM*ml|!cn2T*AGG62-Qj*`yKMX8!Xa{RASP~cXB&fM2ZrFigQpNOmsoAVC zXF?(Fr&SQot`mX9Le@h@n(#Ib zC~*68UkEy;4%-4!0*lw)I4;HFLzl9M-4#tQLx%U8eF+j&D2z^A6AU|C zsPGLTf_hRtmQg40wze4O7#n2wK|)78&gzCoG=UkE*JbDUa-D~*_6JaiGIBF-*q#PH z9$D(fDMkG5WdF4S7g@Lf{_!2T*J7*7 z<`W*k)?T7 zyHNpH1D@;(Hy~mcW}+0h%qVUT)?N^2u61Kh7V~w18q_j?nod{E>-W_;N--1J) z@sAoY%5;V1_dFy$`7Nz_rs#G7CU9ajv`HQl{$ugBxdtc#gcnCZ!1O~`cF%(5*6BWO znXPS);Ht@cndcDB!-C5!R##PZZy_hURZ}?n;YuTf-a@F5c2#51(xolXxZ$WGz5+Vg zadg>LSw|#XL%x3x`gZ2O%cjzy)gW8ys#(@eBJ5A3mpaGwT046p_wji~@+}Uw%+E_j=qsnXEpCMkC}hR8)|qiiEie6*$J1 z&z#ZwpZnQs424h6%~KhdoV|?baqlv{xd`*wb$tWC#OJSm`rRmQe~)QwCGD})6UOf! zK6+$Pa9mK939ujiR&7C!f92}c{tpvPE3Qm5|3dW%TFa2=P^5mXtFm<(7M{HYzGcwh z!HXpY+@QJU=E8islTEXe*;;)>cDFJ!ufX)M(rJ@3w`C4uX!`|1DrNr^$(_&fu+yir zRwY4DxCkdwZP0KR?O}rkwI8tV)AJE$(U-r&WH-{%0~q31KjIX9kEgt-swPf;sV3WGCwwBg z>RB-wGgzC-1uFPJ;Q{(0!8g{7bwbgzlwlD$3H@r-pId*q&z(1KkmL?3qq|2(>?eBE zAA53W?_T;GxJ6PD+()H&8@+V(0X7tLv*5=v^YxI=+o?TE9LD zJI&t~f1Q8TZ-U5Yc*dY~K?#C@(ATN!FG@tHE8{o3p#d`8?pdf&D`Bn5_m3y7*5>lR zgFb6CcL$e*&!2sWfS-z}*8DMKpU95#`+Gb@5~epGzP^CLOYoaLYmA@&z*qMB)#$35 zX!s28n{1wrX@gMk|7qP^S~v!=o<*SX?4bMI`xSw?f$6OTAyEdqPP6Zb>r$L3LLv@4e@4_PvnA_gpyL#H5ut*bki8%uCB# zZpMv($jHdGbR>jyR8m)0O_*Q=FR;s+M&u{$TDMn?w|zl-9(vF58O`Z_CpK`k9;S{8 z@^o?!9W@qq@$}T!ulu*McT~UagN{i^UF_ z3xjWpRrD-l)YM>`R2nNDUk=>Ra!^gn`e=}g)@9dJJ=d!51S|#}+0oFdPES`y$Nl>C z>-Kdz==eQ9_DKec=aE?jm?m$EL9?;v8y|)BhH63zHGxJwV_x<54qenRL7UG6LB@%Q zf%8{`mFGV_slS7q+2dQ13p#<&Qb#-3$x6O<_3KpIVKefr_^I2%!ouDR7rr8<o{o$gKUVC(Uk5&D_=Md?bU@&;ugJxWLVRAgOuuh+I)c%YW)BEF?yD4@~ zV2DS^i%=*4IXj<3u}@on)|}ZILF#&X-D$?(A`6&8TVlt8s4^-4quB69*kO2JyI_jC znxcM^qG_56=oVG$#?-T$Zg$sm$$A(q%VgD2t4V`(bdsSs44d@*3Z$uhr;Spdp(Lonk28@+C$HVJlG<}+}!qI*4B*r(^1Jz@%G)jwt`658};pVf~zK z*$(uPO(j`GjXbjBwQCc56Y%*O!a9lWOf&olHcsotAj18JxLwxo^jdPRFN$wN*fXGq zSgN2QH@x2`nmEG|OrvMq$t2j;T-O7Bb@OMZf7>Y$`d^~*E$`35+M8c-M=b0>&{7B^ zDP0YxP`<@J{_^$XJc@!A6pK5K9qXo7|KUoz_k%Jvoe=qlAjE8G+veN)n#JGGKdCRp zD69D)z5QshNv6y^?gVRbR682izr!v%w#4k;e|53axke#W++m#5LS_X8}w4do?6R!^CCtMjq>u6Mha=P@l*JDs*eV(wHCB6LV(U1k65?S4^C5B zGADkMuHLVPb=Wxw_g*17a!w#pnp>*+sH40M)%DFWf#0h58OyyFi35TOp7?bIG?ZCC zXoI-4eC*>sP3vp6R?K*^h^&NmyHLasUUUgh0k2;6aNd~uIU*>?B1ooL6TeSCj_cSM zcwU^z>^@o^D!m}2jQyBHOFs3$bP8@MLh=}W_)FUi!lV! ztuUDDS)Xc=iAPTPsZ4{6Tif?e#;kqkiS3R5~90CVTL0e(;vH{GELaf#9<(9+6xjwe{ij*z(C9lS z#^tTqc7Cp&XraQ91zl$yK?@;T88IR#cGrJB(J+k>y%wz1k(m*=?;Ayvn2>gBsG7*_ z6TUfO$*%|U@1VnD%4UW#w@7SPqvWA&xV-i9bITEl*VRDP2R*LmJ!fBQ1OhQ;(3+2~ zp>1nt=Scw&ykd*uZDxBeULaQWYSVVS#(jiaLUOIw3?C9D=01MtFYT)OS#$ySVrT$5 zXLM+0(Ou_D3*$F!6Nwv*eZ|Qk26~HG#3=TmA`$iAaN2Od#3$yI&$QbitC7P;(X~l! z#wDFGp{ZGK^b^#COp}6QG%hHy4sTe)%Pgk~`8LvpU&biyPt1X*GNzy7vN22yp|PLmaP?4mN&eTwYk%ex8=MKVZjIlU z#wDL$A{rC)FZ>xf5H{^hQ;0opWY&Vu)B_`SD13ju`s5K+J z2(tph2Fn&Zi1z~Tnuaz@m!!gEPQ*>$m+egfb6f-Z^B0C3SqBCyXjKXEYQ@^ln zWkTJ7^W8S8JbsnHDTvV%6lB6y7R;T7xyh=J5wgm*B9n+IWKfNiL=>%JS@CoI8jo`i z#kML&!7w-vUNK4Y-^23=T;Q9Q-uD3+tScJ`#r*$O`?d&!h3S0*o}+>rL}6F_y-e?W z9ivsEdS=jPo#&-zFinh=rjne^7iN%ZVM)?(M%RcRW5>$0iQ{*ln~QroGf)9sHkux- zBoYd1Vb>@oTp?*rz3NCI8g2}+E5`H~BDAIy7oHUS=C)nC`jZ=N`F(gJ&D=QXb|2ND zLu2j;6%{BV-urQ201MEdsLp>{V%`s52w}b>E+dm?5(#U=(iSiXcIun$2e1Qu-Y^XB0l z)^F_EFM{mjb_ZUnlO#DWuPv3Uu(1cCp8fNMvT^#}si-+i>|+pM2UR@kTj=--N3((Z>IIfMnK(`Y%VS)4G7`RKoqHBL&M6#t1XeRh`$PuASSt? ztNaRj;%x9vaQ1Yo^FqeAfYA{v;_7&iHmg_fW>Qha1{6GfAg7J{6!NqJk3d?9%}tD@ zi3ci(7r>ZkpYf+tAFergf6G5Dz{B=fPENqtMOYD-UIFB?dZm*v;y@rA1)nFZqw!uE z&T?tk2TxewnJ)tW_pRcuIJRzoYQ3GMrP!@4W^qJP0rmBmREio)_t zoFq=d?8WV6)K1(G$qSV!*)t6yBt=T^6)ugO-uZ9%(8_m06dh< z%9R%~#Krsje)a_9Z5buC06JgD3a~OsCwlxg6au=CGc&oHVxJ232+0(voT6UTl3v8V zqo3T>Jp#oMW{%PqrlK6{GI}R!CzjgV%b;^%yepJ4S`-DgCcGdQ4X(Q7_0_v5ZG?*o zTIp1Rqlj(Ttk7mj&dQSEEWCMorH`N|`EE|bjwqPvE8B`mEF8?&zRYUNgsSiTLAtua zT$JnYN7xU)9Q5B^QG3}#X?DNsJq|Nf%7HnkW78DJU$I&Z5kon6jD8eGYt6)dNa&01 z$`26#sgU(Mu+c3&#VY@HIdd8$d0(#E6e`FcO z+~l6|n#ohdJBMjR(1IG#1F3{`8;}L*-y5czvU&#sbN!YK@jm|d-+HuF{yn#9x~;;P9NnIlu5K8wUNB-?K5F8eS+m6V zNv6IaK!1|l8~UsGtRcE>c-}uZk9Ov?ua8MhHD#0DYT{2D znj~z`x>Tw`-n0a+Gmioo`86==*s$^R!c0qfQ#g4D8^w|Pr!!A)2u<(oqAc0x zQu!!`j^9-uOJ(`yY_g~2S%z&`?bG}5z9KS}x{Zuem=y;z+Rm?6MBR8(NF*jwl&Kht zK@LG%fb}ddQVPv-BZ}JYa|&C5Oo{yl<=*Z0ZtATSEUNKkq7jxx7d^ThOzt2BZ`<8$ zw2h$%t9TS69~FnM!TV(LSQ&rp*l!X=qxHYXobJZ*M$9%y#cn6&=T;09>G8m~|&leo8)dQ0Wz<56F2EZ$f(KXIc|k2QZX*zaU3 zrUPwIALZ_Jv?Sww6vy?xAu%|LZjo>Pe0kuS+lO# z7x3>Y!wl&t+P?|F+_C%Yhs}9_17X4}zp{tU)c{7hxc=4P8NTBG{|1>@Yc2;ws?owHD;lhHfojc9A@@@4dgDfW#WUK$}iicwTg@=1R z@vq9v)c=Lq%~kvNLv;)p^G@11V&`|~{_jS}ATNGGLbZ{r zRz4>bUs|xAckC3tmGqPBS6ZN*@}Et+^4HSxt>bZx<05#D8ugfP-mI#vi3!RRm(>1G zVBD~+uqDN#0QbnVV5LAqyGp%C;0Rl1=RGNjdTV`nhP+L8jeg?}3>q+iiQHY;&nc*K zrf=p+3tEKCA)}-|FG=gtgMM?61}Vnr&K!4Y{$PFq@R%@LvkNoZ&(~BLH~6nX57 zGb(=cNWmu>a@b+=KuiNc3DzEXT0$sO+jhWR>7ijw#anOq@SEC021}P9Kkj>zFL_v8 zc)+5CxH-dAvq7{7%cemGw=QsmpFZ>b+e#T6n%oKxJctFUk=XVCW>owqZ%f9&nw(0% z>^Njd9tf!fSZbTy=9Ck7$SL3S<`Ho&VBhzc!(X#$amoUHPDUgh?{-S&X%A0Wh~3ts z+wZzk9V*9a%L_m>CO4im;L*YkteHlKqH7ta59A@oAK`e`zp2{sXmwCuiR;oQgQ5}d zTCck}EY(R@*gLxAxwz3{`hy1Z%AMV{UzIOgILaf!dre3h$bi1}xS`$ZRDU0$K1VNt zf5C{Vl#=N@y*^f=7Xv0Kn`(ed+3~dBGq$mUlZLyH4VyBQr05HKIo^N(M9LGDbgS9O~rPxc`I4k*Kn(NY~e za)cE?mdcU)FE_dWY&jktvcZ#xCw3Q3XY+vr3O{Z3fJ~RM{%5n_KDnqPBS(Usf;ReM z{7P#o%T5@;tzIf_leMvAi7v5Z7Vhe(RH*4zk^XnLT2fIQ_Ho%_8)sGvLi!7hdhOaZ z)%-j7s&FsZ>#DT+ckI%yX$KCB*B%;QkOsifH}G>)>IboPDwtIGUMkZ*eZFj+1R$vE znf-1tA>(m<@k%XSFIvCB1IID<%pFi3Y$#7O=b0XVI$@3rSB{5Tveh|G>46QmbNTex z97L%yx&QDCBGpS&h&)LI@lF-4h5p^T9ai1dV+MJNxnvm=V{%2xScY;b7*_z|L)S|x zh9fFoT>kSt+s96{xKJM#n5IPw%`cpa8o-;9bq zHKjwT#p^%uwy{3g`Md-iHW{%QukVr%E&-QM8SvjI1xk3>3#&g`01asLIL0;@d0bPb zY?w2njouO}R971m%W`*_lj~BH0TLvZP@Evns3b2A0O;~6DyYX~tvUMRF$Jn!bYKU7 z!3&Zt^@uJao*yubbDF%&@ZGv2d`{`A`Yx)hEAujU-o9FbmRUshi11G@=*zvNLKU|F zuE{42YpZ{I?BU=`6DT_$_|4KsVaJLEs--MQqdpD$^UvP6cBtaBC4RpM(+$70!NH{V zN9p0&$St&Rq`9%W>Ne}8o%B{@zIya#%2e5gk+O4VR@LBlnJls+SXJsqx$pOCL16-c z91NUuV%)VhMLyqqg&0ZM2r)hod#8d)HeU+OKeA(Oke^>={i2b0_v0GLx3Nieio1sB zRt#^@I%uA{405)5_(^$`YZrrGjLQmWV52F!GH~TUDn);Rky4wYPt>e7lnx$$_NUL6 zt4qXreL9gGvUaU&mhD;+4g&~pwywk`Y2~=0$B5$P)3~|a=o3#X6cA>}$qmbj;X#0r z6y9&2clmN7-of(Cqbt5v-NL_@V=Q6|URmzBHPW?G%`!T$=2Gc2Ow>7c*HB9`f~h;k z;OB!&F3$5_qisSQI_WoA9t=>}oPI+!>*8}4H9RQuo<;KZmrtJfRQz=>CY9>l&B%Mg z1O+?`Mj$p^Zj!NDr`NrArlzX-`}I=Pj2WL{IkdY3li=A}igqun6`1l08x%#dLo-C?;PCg05{!58+fUDrOd#BoNal;#u z5J7EH4B>Q_ed2PEAytI)liHjmCf5#4c0O_9gc#2;R}kC#x1Z7Pdi{wO4()jz_?oi= zsc2O9*pajuGc;4=iMVyl<&G?8%?%k-;UcX3-ABh;E=F>!G?pc@ne0DQ2>&3d2puD!~%D#WP75;5m^4H5d zMLyMQ8XL@+-7w@$;j7kR&$?9ZZ)~R4@xU3C%?lRIyRXk?Qtw&QzgmIp3PglrDVmRB z?sY;FA~KKDk}>VNvG_vKU?qG{DAwA_VNM>d{4>%ne(*JLO|QR5iVj zfOb84i0+JG?kCF+{Kc6ef;c5nO+?-8QSz7RoI$IP>o0wKbk@XEi!*};kGZ?wSgj); zK{ zmAylZjDRa>_0Dlz6`AE;#cW(fWq+3OWq@500CZ`9iSrz5R`H;O^d`u`NmcAXiwpG2uA<~LCJ0q0mLY#5h)q;{Q zqe}|>Lh6j(t$qfh-FH6@(RHfy`CAWC}2V;X~fHtl#Wr*nDV>)nwlT?vl-1p(^|>wsT^Q(`XlDK>=}HJzYndp zfNBHoH{J#cQ*ew2A9&-4A9tn~_B`O{9-(Z)hFlk!6YcGJVOMbo1L_-E?m2lyZEg#p zQhF@B>7q&#v!UBo@s*9KsjR=g)8QA?C1nPDd3hWIFlB6XpPwJh-Y_cH$X>TU4V7%- z;~$G~c-Y91;lN1ZmkRz-f;z6=)KxsV-FM+KSkCv!_0Ejx(`90R8jO(EuH<5%8BwOm zdxUHgwD1kuqx4B}mQ;PDuCs7>zHGr2_z3W%KM(5-c7_tH1=gZilldE2Y(`{?|Nn^Q zp=n;P_3r+l1sQ;COr!|%4cIiG7KCm$UkeU9uD2Nx&@l&C!YQ?K`TpyeBLe=ypX~B> z8jyPyq!2*Bmia6}%NKt{y$cXMkVheIKp6i?fTe)X3s$M~ zsH`lUJeEG`=Pq+s%RFz*WQ{baXhC3@mP5Ao3kytWagwQ0MN5ZE>cvG@um)Ccqy)h) zvLU>CSk}O?WAz!52PGO~VYZ_<*Z9XGiT3!HT_DonGB|lwJo}&j z-BA=Y3^BCefgUA|Rps9gKwck{hIt%#A1-B>mUT45gJesMC*Y~Dx zt^JAfg}Tk)EgRzsAbz{_?y|RzzfsUK?!sBXEvSc*ef=#qr-thhML1_vr_#KVd z%R}oVbYbD5eYQ#2v{cvd#EEU-oLhkYklH;=_Tbpri9NE<?uM9F{>2o zSy%#r?PwfO;%M~j*;BkG0F}jB4*sKqzt7Jwqg>upV?bk`u0sk$BRNu*a`B;7pm778 ztIKSr_$q=d^aI2)^LOD7ey&T57RdnTUM6nD@_-INwz|xJUAUStIYu(MuUKmW1=4 zWw96lX=_;pawI=ldjFcAf^Y(@dpp3WyzxuFhJiZB37|xj z%~r1P3;`9n%>dMrZ)x$e+QrZ^$<|2x_42`(6bgA>)DRhgU*?08oPN6)8UREx;sMt< zA6e(hZe8QFIbP>5d~EK zYTJ=Z>?(F`V}-;44Zo40Wx<=NY6mn|_xnR=yDpY|8&fKkbPe^1!A@V8vCL1H6&F z%H%GgPX(bRRkFW9vC@`H;dG71YQcI0*p6oGUTjJ0fuT$olO;0?Gg|;w81~%>1TXz~ zdHLu@k?BXC|8wg2$0g4o-9%lG8g2i5P|`4&xE5ZKTJ{YY)0>V#Vw4;c#8YtDg6_#e zT;YE4!uy|G(m?KHpf+fes5(FvHujuj!18ox^X0OP1Z(QM>;hz$Mrt%$INWDLdFYE% zIc+bOkZzGr7DY!d&VfvomPfd+z(z!!>C2!9%bzh zgY*)}4{>?qS=Wb*t~uclc2uC0(?27}!U31+2KgsOL=6Kjk@p9eYea#eps@OdpeGlB zeonh>%8dy`d&K!`de?J3`7hWyOt+){@+juX?{r!EEkM*iAx8aq!NRMdL?G|A_V25l zifT9%?5@tj_peW2{FD=!)`jsLnM9xC09jTbAL(NHGn44n(PLS1 z#X_cakUU1SyH$`fMKF(jB8vy4Tm!5y9pd2DJE*#sFe)g+9rVM}ykakv%G5BlnbNb;YzD7 zw!uH<*!cC13I8pgj#4Faqr&O@`PT3iL^hT+=i{g87af#5?D)N+~0h zY{SbxUS~u>7kOHdnsrr#Z$w%k69bB1XfMQTBA5w^U<=YaJxaL{v{M|~CSaD0xo*0I@fmz=f}u`Kv%GraaU$Rz}VIH7a^3gjvHftegdne z@+fiu{51$bwi6~8DdbEDA^@1My_D=pjhre1f zry?6yCq@fmdui#Wa?d3LQnw2yj~FXQT;{YJ+EH5~IGW;nx zkm70KX>nc+BbHYFHJSQblbli?3YmQJn)E)>3Bwl(T68ff|+ZyHcs|?#$%I8ny{?sKWLD6 z2#ORf5{8Y)@yd!|Q7$Fk3 z!=L!t@~;kE02Rl?rnGSi1*n6|#x5%S_An6WoM#bMmvMXKh^g@riRzCrfZNbpJ1&^w zLFgaUKhhpy!qdiJkJrhrLh=AC{((&z0npGthJ-CFk3s?cD~s3>uC$A-CU@5Sls1=h z|IUdeMbIW0ENu{f`~L}})jNuYk$+=vh~$`I819^^0_$_J!YAc#mjJP=&F6*8nVp4& z233}-fZEW$+`&Brngu-t5T39)`TVhK>`@oEh%)%v&6^!=Z4_9W!}|7RVvpbT5ciHE za@793(@QX05m68-Q$2{XJP-Lqew<}T>nQv>Qjle2l$-{ngu>1g3WbG*ERpM_5NB8* z4pOH7 z7Ca)51IL6l5fKh?M(QGrkw*v`pa8B_k;a&(dgiU&u;fGKT=pE^XA=-*Y8%qtuyO~J z4E74MDM>ylbavkJlM zw1->BM5O74FnP?AO#~<4wz!EK?f=Ai?0FRm>X!S*X04?2-9fa6Ef`1|&Mlb(AR@|d z3@}=1ge9A7`$@dIrn6GF=~Zt{W97{u+xkWV8np)URcznCKbnd|`c*>fhF^5|QS)F4GW1(+ zENV&iFX=2`UQMJUOG3iJ_qKoKdH3M(VPhTePyE$}*Zxj}hBjFU}1C7$Y&F zPJ^sug8tjtN$v;6>C132hkj-2);}r=*L$ti&yAJSc2XPQfB__L{&!IsDzaI0%iO&^ z{~Z?2WQYSiP^6K1uRoq@a-oEHPy{2p+BsyatQX>fj4uwgzoA`MMIKZW>uLozgEl}H zBqyGaWIEV;?i$$(C_iZ~5mTrW#ZYA~uP1BI}M zA_fN4HCJuD_&imB1*63^t_rpJ+;zIRs5LU^`*B?!3pn$@EC7~Qw$uIjh&E~eb>Jco z$Q`q1?xr9O02Vf-1#uO?2-&D15yT)k{gO84SG{;n&Oy!4h^K9ERq}>&H1+FjqxpvU z<79v%@e9CFqX`wL>{y~>mc2R+Z6Y+f{QkE&HLSLx%j}1}1WPQoci;T!%a^5<&6(3` z_G^zBCi7?gxO~RD9q0va$?Yp04d=#y%xZ456xPh*5Gq8CDH2i2xDC6FMbe@klFjq( zpA#~feaT!yLl+Pua)a;-D50|wv zkvgu^*RNfRV`8>(iw*!GB#&ImMkDo^QBFTXtZulAnT~X@x*@D-kOPvI)(*d96-)yl zKO0MHM)xj=BH*}NJ`uvrjC4&>6rqS{?2&pk;A+d}CNw@$tAS)X>90$>EFxRpwkoHK zF1qB@>#UOScPYjuCUq%+2K-h?*C|>TAXXzV@(X!CAaY~nUmO$3O5QLUH9Nix3?w9W zpLR__wvZJz(jZbJFyt^!;8T+flA#pxNQy#;;8MksCwMs;+;2$*ymz3bf)pavc?eAD z?y&tO@#lqTYBL7k^wJ5y!}C3h0*0Ia2dl;X_Cg-bhRvIQl~Hd#Z;5E7kmfTf8$m66 z9#3$DUYz14Dbfp>V$<5}3|lE_P$RH-Ri$_r6AQ|O2{i0j*e#Q zMD!|{<&Tj0n9@W*B9{Jsmxdh&T3g!ilxSXfZaZwpmsVHQubEND5KA$PYa+uc)Q2Ik z<;1CiMDgU|uGq6wTU=)#h@^tl2(vApW|BmLEFrMM?9ycqOftZ;mKCMu{(l%NZNaTJ z^sbHOuA6`(jg!9<>#s4WEk+;Y@Ej^y`O36~#iGat$dqYU1Ora`aS?QK%#8^C1n%Qn z{o9|Q*HUe2wHer-S4qGs9fLkVhI-McO#r8Lx{B#2J_-D4x-;&j5byx5%tF) zIN!Nse=(!ye>n#b!cOQm^1By@Ge0Z13?z)K9P|a`WeBH)9V0eAJ|<$Vq_<4daW9cb zDlKd?H6d{r(()~6@-yBg$K=SXx83cQsv$-VD8oeNOR$q=DOuH(&frB8!MSHnA7bxb zfZda}Otj0|Gt4!`kzck_0U(RM9hWf5Y-jy-5#NTAE(IN>%_?DYh%h2JO8)P+Z6)6} z&nqJ3fzkLjcooruz-+TvTBa7M2tZPa>(Y`Fdp{*CRnPEp|>=LcGW?UadFg{r# z3ng9%btr?96nGN>in-<5yG)W}Jn(QLge6m1%4!`Vx~73aCx7#wpFG(uhVIRN0L{6K zmPsWgV6cRAegVc@VW&^``;ikkpH|nXaAb9hBAfP77D_*AWSMmvNZ0Uq`}P20sxU(@3V9C)mZVKluX z#`$O6la(#d5-5x7DkRICV|@=m{e{wiNN4v#_ucLdAg`oS zg6@$4A=qB$|G6KxigTWk6tlTz%quqpS`L?yi;}$6v>~FEm)HkdTOvD8MEgSxAki2HX;Nun@A;rdEEoW{6a_W4erroh z0b0`_@C%NL#*5oUv%UgLS!(C+r$3<`A-pdmS`r@1TE0EXFJk!*+QNqDMk#JMQ~A7* zU+Cq9<{XB&WS;fHHwt#3i`4@Mf=y1tHyXCp-GLHS>Mee4E}gYPL7`HUnb>g0M!uB; zjODSLozKfXHkT8IR}0bi&K z*~q1i9DZYqNU`Kk+aCQ z^D$#u0=P3BtX+k#b${v^FQiCD>gNXaJ3s@mgYbtA#Fo1!w-xCj9lH)N8jhbP!6U<( z9@v$3ooLz~2r3IIE&KWC`UA?2Q;BeJ0B zx@VDAhyuC%&VkPU_QpyZV!7<9mBB@Exs;hcE_dqx#PIS9p)p_Uf+kpv!p}|$3t0t7 zovl#tRAr3}k1dSUnS$qpdBl6vEB-`zGNo z@rd?`n;!7{)Ya_TE6_gNlu4T3#DvJ&`pklDWlx_*h&l!p9%b#)vXfE^Ae`Wtw0$Mp zGYl}C#sBN}?S|$ii)P_ZdH3{^;{{m=xz69b`F3jwigbN?#-k_p@f6{7j&CdCbpr*S zp68+vXpcluRrvPlP4R&f>nA|0oZ@uu&;+0=x;MS=4>P~Lef9&8Z?P%D>8^~{GK8lP zq%&i}*^r^%dd3y(q@Kgkp=`e@EX!+Rx$5JV_fxaOhiH{New^f{euG#g(ije*cGW-dPS)S6yD1*gp)f_iyr4Ny zqCFIsE4OFk=FNHw_mU@I44>534N+wC7CkgodcQXz^@W zt|(Ks92w__OP}2^r4h}nDr8)sxph!xuU`fi+G^4f@i#t(S=Fuj%FavTMYH4Izr41N zvt1(u0V{0eM2g(@E0oP3)G2)qOC*tGEW; z!I8*dl2GKr04Kz-0Sq?F3ckmb?-H=BUzi#z4tzU}(MKN;rGuyrNW{i{(202d=nd`d zQP0J-BED$db>s@Z6U0$@jd zf#S-2`?~1N0l#mQ1s-_~8#K_0X~C8%g7v4o;q96#@8Eyabm4&*;Ioc^9%Eb00lmbj zYJY(x+@KzyT}Qwu7tOjhka*3OE}b%Ya(cok8YEwHinF*$h&PqiD~aim!tm|%+Y6O; zjw6y=!kkWV2FWJkOZ{JdHF>pw^9CcED}q^BiI`Kuh`e6RGl;4$t5>fMLroF4R~*h_ zxW;2jJp%$VaiMB&V2x+(#GqU6mXT+|Xv;N-i^W&}TNVL{eQ5N*A@e`ayr)^Uv=%C4TN58Icmdabvr0<9|ShR*p^kP_4!plP<)M zhy+uEI}m||u|PT?%ZITKd4Kxm>|xh?5sKLI$I1 zY%s`ODL39Hn=lxqhM%HBL0`Hb?DrBM%mPNdyiO14zVf#H1!r~)$ zH0L>0HxSggM}c3zeq|J@!|dbi>MA{f0;16`zvRATxvh)WnFX&66hcc-g%y7zAV^R9 z@NcMTO5U88qGdkJ0?Og359%wVWrtkTtSdr38Xl?1rKkg9e~%w#g%%g?3U`!)9U^>-BCX{BBFBL zrBXTJ6r5~CixM0W!~wy{$D;4w!lnPebji8&yuZ?bnFO6X{KuEVCaHAtIqwO#6v6F_ zECKPf?y#@o8bfu)4x@Vk4d~p#rU(t}Kel6=kxFqp8)&-3M)oXs=&&c?%a$I$?>sb? zc;QR7=vVZ5GFi#@tG~qsJ|vqmjbA19@-=?qcl*!3!FD2^)1IhJ*$afa>C#M9;MP*cTU$euLo%f6Z; zbBYXL&I)?o{`J4cbHG{Y#N4EW<%`Kgmz1zXi1QFYGOW*9rVy!Ufey{Ddxu1sFmT1j zsN(tDfubdU(Q&vRdpmCY8ll6X$v@?*RjYH|i~roTX;jjF)I-Y?lriPmTL=H z+a~HDky8v@)m()r%hNxP27;t`4wO43+Vho|9}om!Ff}u`6_$=g1Y-TvfH(0qZKmnP zn>UA>i#p~kL0)vOGAQ`^WmC82VPD^Tw_AFQR$T2B-ep&hzvkbN{XWO3s8`b>JccF2 zYQQB@@5TC&yfPWkmD3E?Enksrluv+`78cg*FtDT5CJ+u8o#RHfK|xLT`R}`N|9z*{ z8Qs+RPLpW61e%qdd}5FbdH-Y2xuALE$;VHgD#WG|0 zu3cqguHL?N%e>;ldyn1jT6b`CFIy! z7q0$|p|aNk3|;YZNb&R147H6Juv?}x!4US2I$V#N3Ui>}$D89gttjg>3{_fRW(dwv z?unvF#IRUpXA=Uik!I7SRIdGrYc4H%oU1g{JiQ8*g-wKyl|A1AUvb{f@vdZ=5ok!m zBfI}6fZ1Yzvf}v@cSfje?>c$t=+XDboEjbwkvV*?6hNAxF`Yi7n*moT z+gCP~0SjbLB`iszfp3tbJhU%O9JC`47jUW7#3u_M<2pKhoARE!Js#Kf^UU~Fgj z9vNPz8I#hRr(IV;KbQ80>LTWT5wyIyKFVr6y%P~KcNXF@G-&Aw>p+URBDQAhM79}b z&}YtCXT(|s8RWV^uSXi?K)4$*CFM+K04|fbx6@PiLb1en>^WO#8w=6l(DVX7uZfEb zgLe0((fQwYRZE0*%C=x-!kD8{lMU`Gm}BCWt8uGDECp8YJxFcw86@v3QMN2tI<;z5 zCUZ_=2Nn4MqRWQR)dge-Fm(sv00f1-*PTL^FK@VY7oVtjG5`B8a-~>~QgkcdHCMn% zdhFc)2|MCp7&$;q)`eXa{E;F?Hl1d8rovkkf08MB+TBP0{ww1~ORt??d5+E^=e_jS z0&#;Z^X0lMd^14?t#J#@-cvTh6R@G_oxp$qDF+uWUYyK_Vp`1ZdcS3UFTjn2Hjsyg zW}VZQOp_x4joHBvV!E^b+6bi)fl5l1+!ztGBevP~{lB)(FGg^P(p4Ka=t0khOZ&<~ z0E*N)6zIX|+_Hh73kwS=8`kumk{-Wc^qP>J5sU7GJCN~cBr{G>CQO&Mk(9sa_mMGG zf$e$_lQ0>Ipg=B?rMoCYBRQK{Z}0b9Ek$wtCVI!`JUpQSX`L@7XCQAH7liQrSggy%pK0%3~iO~C)^bKR4Tz~36a_YZ*c2RH9@D97jz<;~_ z&E5qtDw6wND!J0TG{J1v(u#{VUBs!S>zOGY;+6XI{`jM5!!dyT{@P67x<|i%yoZ25z+S26(M9c z_cz}iED>%0{>FTcIMsj7VZg7`a3NK?`>l$o%Ost;ieA3Ob;*n##Z^`C7u;uYCYDJ7 z0sW{Wa$Ojil6xg5_tB#XvWXW$pu^gk;GtrE!(O*7+8u9M2UVZ=`0E+2oay}WwO1;3 zh0BDcUdF~3DIqjiSU7jVf_xrRRH*^;12QMttWys4N{!U&BOa-uyJ*>Ri}%SnqbRex z)|g-kuMO@Q@Xix)q7)mzO-RlK%;Z}2@6@^9`;Cm)3g7{SDm$$_fr&a4D#m>^Sj_mE ztmWm(bD#G#^>=s-K6hgN%U@|vFwJPplLlo8yn*6(lfX#a#tD-q)#=lx&jp`D#!g-z z`XSE{tp%+-VMGA{gr5J~h?;P|! z{OGi`@4#)mcbwFoNl|PN_^#h?dFJLZA4@cO-ESy`FQTF}8B-5enh=@T*_-Z=e~a0P z9XlpP22F6)1LRQ1!{lA$j(E)j5RtEpUWwRCcN~XG*mFUD;MoRn<$OWej@f%& zwNLc`-4R_NE-B4E|H|c;#%$1_UCr0IF7o^SEf80o<~&7jEr;*lzA|H1ba(>V8gqa$ zzHvR!2{9`Hkq#FM14kaWK|B09K^mjD(>_jaImF{C66ca4LunSNt*5yYZfOq>M zil&AT6+f`4+WbB`byYaM!$y8z`r@Ajo=r!7>G|e$r?LGvCkJbU{Nk#zM9t#w=1W#* zutBX$%hRaJ+&|C^!T-VTE?W9H=e^X6w0(e&aQ|^R#k1-=e6Otjq(1|jeD@kLeHmcNHJGe<-Re4WFk?o5$DBw$(3XLp~y=*{~pUMAz}&Bh>4IW?;*U@ z%%tmtD{KQ&j;;zZ?EoONoc!OuR9qQ>a=~}J**Y6WmS(vSpApB)z^Ja$9slUzN!lX? zkk-~l;8Ca3V+>6BaW`lHZ!PQaG!&uaaRIBf>(;f=l-wa_UX+4IuQs!54E;|^k!!r7BD^^ox^kcPM>fm&D4Y>x4(0E+A zjZ8^w-XAt;)X2PY(uQr@I*GSanrBAx{T}b1Ubl;gj@FCO?=i!D?Ks0angV6{CNShG zM9oQqo;1a+J9Zr0aY(9Ld*MMsKoUnAp7iP@8$!-;?%oDOA3jb&KB`qWe57IdH9?$i zN4LbC{td;sm*HW^A)#-S`7N6_R~L~~73IeGCuL8DGu;ZP1&STpyJ<~kNWRg@>6^-; zHoTdEx0&YUik&C+idG2;*JIFBnaDt69s;Or%yy0PF3FBU{u}mA|XR7yz7&+r5_c)C45IPeT1$5hm6Wdwp$MMWWwP1Y znFI?NWLmps&33n?ga(`Q;neK(QUJJMUWGmT?fFR!Kh%|H-Gpf-6q!)J}Pn>vfRqEV3$~dkQ`I ztbE~NXMzIL&$luD>;nTS5V}`1d}7&t85?UoXh7KQ+o6|L&ie-TDMeu0C>BcKe(KQLn7 zX3s2Ar--6n9fy>qIueOLC~3o0N4wyFmJ)kQ24`iigIywLiSLTcF$I%388rj06kgTP zas%ehJ$QE)3QOgsi%(|OQ4n7g!ASAY6uqGwYQvhznXkdRs9;twA&}5_k+uT&1V;(! z#PND>Uin`A^pI_oNpx5;a3zDp91~TM=h4czZ+o3!!Jsn=C-+uwiT=eFWCEEML-E_* zY_|k4DeLoxE91bwQ|=Dp0Esuzq)Y&fM7Cxe#>HDg-T5&@p?qCUEtk5K7x^GC_ z9=qp=xlRe2F0yv+XD84J6IY^3&S&nG29lK2B3@)DiLN0v$Z;d}MV)nUd`UZG?rq%6%Pc0%CO0o5?KgzTBG+>@8At50rkoyFb+5aJx zyRy<>k<9}UH*bq99uI~#DhsQub3l)*W&|jNE<w128^G1e2-S4A)?KEx|RK&rIv(4nD>X0R-qOEnC9M}kgl0^Wx* z*DP6pR|HtrPxe0%Nu2e6jq`@EL`HMsMB-_&2~P7INkvVg(Ckwy-nsWDunV`}uZ{w2 z9`)p{BAdva>ql7*?XdkuAr)%#mMz!#WCnoF>UICm8F0bGUh;XL}Izu`{Z@!(ioTr zs23Fl4c}Z}Ulj#ds#o8*xoM2sut%y~m^mt?;({<|lh$=`q-)I$`6XHiTE5Km*5 z+Bha6%^mbZI&KDGEB@+PBqnqH|M;W34C2sOkwM*TF>Ekd?$cSTjsiMM?~>)z2kkUq zhGaTKfdS05%tiC!K2TB1+W3X>FMMXq&`_ieOA1->V{bqrnV+%c&a|0=n<72zc@S zNy0tB$^=QuLabc0@^En9hPGSA2IkJ4n@wYe8A>EZ`20<(a6%J}!RfUGOTu1Fwk8Xp3$#b0 z;6x-{FSDuJ`Yuv^^v~)q+_$J%+~j7L0LSb|l54NBmc7FU(8F8zkyn{*&~Mdhd-|tW zZ*45cx5Tz&_q&S)1yGIK?|ae}>RzG)*NM-*IG=kKGupVGLd3=!hP$}|5v(g40nOn( z>RkIWO8};~{dOVYR>-uTw;`0j?boa8wno(H?{z;l&DW>%;5PA>gfGb`0@wA(Yg$)@ z#<6pk-)f$Yv9ixbIYGGv2;^n3i*o7_-U&QQQEG$g+F^EyU1L_0Z6A7Vfl#2p1t}kX z*;OYl2vkvq)Nx#_!%&MDNHLDV$;?J=%XD5xf9#%8NAnlVeP8Y&A|-hi(rH6Tq@PcA zGol6_A5fttjN?~=!8we$A6C72Gi=GeYK*MkJ-^e0lwMHPmtdiJiCaH%(O;yVyryOgajppleY3I!a8W=SK)DR`;3@>WMj zi_(PQ?1qoV8V4RDX{4EkK5=OdcWVSfp8VSs3QmMFl4LVxqc-Yyh8b=FsSCa3k3ogAMKKGL)$a}rUts;Pd#CS2WonP_| zQw%V`FznDY9z^ZM>7PVxBlgBrGAlSM4*JHxEP_aRF>5XF5vY=QhAh3Kzo+}TQkQxc zH_co#i+AaLk3s=>BOm@nz)~rj>1S)E>0Z6s_IeTfi}oMd>qu>m9eOXgYF+waTgEtp z7aX`ri_y_QwhCutGEpS6DxxvQL5y^=_W4PoC;)J$SD?&VGJ_1JM**|-`AlQO-L_#G zFu}{55(EZ8g=&GLitN6`ph%{y#4DbE8e=sTQWo;7?xV5AgJ>DVf`V@NJY%^sRmXa7 z#RMXqLd5cMCad6Vw!h9af(!Y9%Vk zZUZqbxyTOc5eg%QLk5%&vyxpd6KVBAK!Ftf6-MG)4jZ-)pwuhPLQd?5eKgBVFMf~Q zVWvDOesctxG1Z$G1lP*?@~V$$+1$cEjEV~{O0;*cq?Me=(JFpDfk8Z~66f-R1^fP| z=XcdXAH|f45d^#o{ zH&w4rMP2s+u2_q?IgJ-3?2q{Hi7xML;5NcmC?$tp`TcHPyXN>pKzOBDk+VDBm{*z3 z{sA|I5uLZAzD8{coW23oNU%ih>r?Tr4o9pcYF!Lb?0H=kZywu;?pIX4Br@8UO;f)^ zS`<^O7k}eTiF}s<%%#z9BAr&zHpqaW2<;fat}7#VjO&PI`1tItCuaB6(hBU&3KdZ+ z1R=ze4hdf!;!S@)zeBf@TpO&LH)0JC|M?p?y51=foRVfd38w7iu?6L~8UQlXS0IiZ zzIV>wdp8yM00=V&>-&Snhst>3m(7^7avrzsqFS~AZAZ5J!2M}?O4|n#B3Fqja z&B-w-3W9aI^zx7fDKiXppf}k#4S~o0e6ay07Ytvivasitt6$!;saWgMy~Dvz+-aG~ zR%w^F#jfMJQI5{Vz%ye%w+frbnOVN6>&xu_eLhB2$deu5cne&jq|f={G*5efQRJYYZ};EnD1u9z!1S(kjOy9 zOI_?#+``|EA`c7cPJ|cpXoVOsfKp^j(=u^ll3xJfKeuQ0ysn7yc&C1W=eMMppCoBA z&FcH&u7%>Y_Fl2E0oC69HFJI2(h6x6&4o3g^j=LtAtDnh;}8P>t%-3RAgB?(g>r@? zoiDILO3ZXs6f`hlEJ$7!h@>%!0X*U2kXogUI&6jmnbpUKd>B!s4jfodr1zrr>~!^e zH=9wTM#-2CCrA))itc9RUSJGdDtjz>h`ix6nE`V%)wJrW@K+FQL*eRX{JpmU&}y80 zL^0Un3X)U_<%P^ulk{O~R5rPcn2^AMW2OqVBp+R$*~q9?;cn?UBppqC{a-kg7595| z?_T*5cd+FkSF3R+jVa=&7E#EorZl!)3Q&Tmv6thJ! z_y4$HpL(0hk_F6>zz?bm!WjcpAouA1QmK7q`@GUSy5iCekV zCb%FAQy`;${q(uo*KV1gnR8a`$>~jO(2*s5kt9Py`6<-3w%cI@q_k?QI-lAX`ecRt zSqLKjzED~jQp@nPERX^r3gws{^*Lpm@_=uO8z4Wbkqz&%13dT(fR{p-7=<%aEOAZAA(ffFZ8P#_)^$D&V_ zr7m@0;niqKWE!!RRX}q-m<$S0T8MLi|1|qpSr3@fcv)>fk@oQMWjYpjZ%m&Exz)=* z6OWQe@qh$f@XM%j|H*W;EJUD!px%8W}r<~MASYPG-aqm3e2ES zrOjLtdTDjt%ZqM747Op+i4Y~$-#;}0lH{abwC5^z%>k<9apj`kUyBBvNH7V7r^DdEalQW& za4Sn{N^a8|yjuigm99AP`)o(KDJl?)0R!A+=oK29F8C}Pd6$v9afq%fUIlDfLc6Ta zxIp@O2K0tv(O8FQD~2|p1;J>Wl875bv339R>(1AHF%jNz*UdL%U@6J34wq3wzF%%v zGuMd?LV`J@+0gS0%_tV zHP10_AzTnHYr`MFxOfx*+dX6wW#ugE1IL)cq1#M#YXHK(Vcwn&`#;P?5J@xachW00 zVa!~H)PA5>2`Q8)M^3Bc0#;@v^6->Ei%ICx7veJ^8ERj zy(Q3s^5JMA2N02>{AVUVWR#L>UPRAC2^9t0&O|00#V3Jg!!(*P?G%}Ffpio_IkF1* zS~4zYK0d3}=FQbr334Nx>f_kQs%z$zk--=N!kV8slQ>3o(Co-oYO_cfZsX@i?r>MC zY=3C|8z23oS>%&=``9}>4;*L$14Oi4Ip#_r{~x}Sj)52L?ZfgGY~hOJJVT+m!F*H* z-YI<-zf%`z57?%HBx4-ILyY8wdeiwK0(P+&==|Q|mtGb~N zXMdb3h$Eu`VaJZm-`~x}C*FF%R;DbbZrRjk>X%&!i%gFH$x9@|AKm0yxw)U|nGfgw zZr?O2KxaiE%d+SMqw=#Tiw*~N{x_~&>=?`AzhM-_^^6=7rlHI9g_U!)z59OqZiu%d zs1o}1yS%06(0x{>rUOhZO-?1u`%duk9uY7*FIvCGV(0I_KMWtI8fOP~hJjTs{fUa8 z4S6Djd-Y0orAF>x9y`_^8IugV(PhfOigc|IS1a)CpbSj`(2&;{@le~c@&P#Ut@3ea zg7zIc;^5o<@-M!yV-~I@UvpN6981XeZLjIifdt(P@LE%)ZELx1phmYZ7~0QBicR6l z@TXDUy3f2Lpa9M4Zj*@2Gc8)SEPHSzRNJ`VmvuI27l6H}M`h!Mn5DLF-+<@+X}0C} zY5!iXG@k~vj$~Hz@T`XS=|YIqMzimAww?EY6N#_M3N-OM+)|y`G!y?h$y6CD{vwE^ z-NId!H3*w(Tph3znYl*iVd~$`w2<*Q@%TwUZ)E)Wg%CxQcix~Eght7^qT}NlZ=F+I z^Zr`{cwu_!evjQrYo7;Q35_mxdctqR$aU?)!}q9^N(0|kPw8@@!$owyr5szB42zDgZn2a#wg`CM6z4X~#5(Fi#&lp!(->}9EWtlQwUia6-3uZmwSgNtDoaom{gfz(*sI8nN1@LdIXmkl|z z8Wc+={tG3utQXHm8SrnQzvy-W` z51G=jurN8WZ~F(7t;TKFbA)v__NolpievHX7_B(f0JULPWS9{bZE+gr+UBOjyr`s5 z(bzhdfvjAg$QLipzF1Wpa_q(B$1i%k_q$TQ_Cc0cC$#+=dJT8DQu)RI-t!B(-JKmj zd|=}W*pCc2h{-7UCuw;l;y6`94tO29#9ui0&CX1T=SoLXn{>6?Y}E(rE0m#5`t`J2 zmvKOriDcHb$s*A^C9D12+)N=b>w zu>^n4)_~91$s0C|*q?Y|>Gywk^Xkc|IrehbI@PgtZ;TW!!qB0U61tP3IO1Y!8oA3o z9Xp=-Caqy&T3VWI;!uW$gx9!-L*?!fBcaQ&813R4>R{|rul;gi;=$hlNAaK@U;3O^ z`t~Kh`gLffEt1Zn=irL30L{WF+GIAh8a9Y4ygGe%8L4Jr`DD2B(4iw88($n19TOui zvN=!0=|L(x3ZhH?<|GH1Q$*i1fH_6?tkIsHZ(}y4$m|aa}KMBF9$cl-r8Sn!1 zf??kU64VL|Cc0I8eHaqk7X_@%V&2yIqC*8`4<6}7mCq32su zwsIuy>dbvPn?7z+c3F?_TKX-1FR}#`gm4$59%XP{7gm4F=yl5J%DoYQA)*q2`r{2E zNF0=UfH8g`i#oC`%hFOtIvFU#qv^YQe63#E)C;gg6dO|1i{OiHZ7v!YoMBFT?rJSg zYs!6mK*(dAxGJB+Me%=iT6&?;T?M0Lsj72^p{CK5*Rf&4-)%E{8z*0NM(IL*13(WZ z(%}zkvm*gh-3m^AFTdTPqH12vBbYon)vrmnvcSu9T==n89}e=|n$~?%SBLf$|Nhld z)ERIz-j(?Pb89zj*g1bMm=_Lz`;O87HiT@_wjV!#I#Z!}dG(-tPabO+5=@WXrf*-b zSxn>hCuV|>$;@L$3_BP%wu(K?l%{X*{?c8?^b-X(&QCSVz z+#5q9CKGk~`diDSb*7yw=;3OzgxzonRktIueb#6@;tmoP_87LPcs^2`qa`R{B`Y)f z9<_zK6j;zCVzVFP@(Ah#x<<}FPP7zanJOYpyo=}uMBgEQ5BVL1T6Q|aE<*xh1^b>T0AwgAo5*ZJmI2KKM(JgrJ_DY4n9SKfdV7=k;TQh)<$z;aZgS zqOB?}isBQUW0}xo)<8dbVeD=|a!;u%4$mZD_gHJ39rydKf*C`7?4fNn!`tyiXh@7lSum?nbzsCQgUvp#(~OKG2dYUx6x&qik9oY#7wJf%UAhBe>ykgSNs z^+sHNKo^%Ga}dV@vEpFDvo_Z|gc+$bW0*Sn&>&KP+!{1}ulE{IXPRDbb3FA*M|1OD z>*}MoPo;&~zi>@FPhFPXo-~W{iD$Hqf1d#C34pX`HKUsnnaIBBrcs2Jbsahm+XQsm zfa+58xu`D0I!El%NE;br8TAL_l;9$&>?1R7N6o2>YXg>Avjm8yBBK+75`vn;WaFgT zgcpXguBH4F%4vlH1p<~nI%59|RpHmqxAq;&xG816K%IcVD`0Enx(gnLW~=sl7qqa^ z6ytqr;B?bK`vC(UlQ5Qd&&@T8QGV&TZMWJA3<*11kVhTjoJ6O$;SbifSYRurQ-Je}3BbL!LJd&pX zL=E#{d~DN}EwUT|$)zn%LH5ls=GkCJYV1I2dq{Wja^X;`C^)qqj*T0rt7r2?W!enn zP4?1=?3+gK`rc99hP0`1m31$`q@V#&qq$W;FPRYnh4-fW^~A$&mkr)W$=>mZ&@tU$ z1wb=!-r_qv1SWeeuLh9`-A^ssa2lD<^4Iu;UvImMzWdwDi-Vn6fQ%9ZvLQ_ihZ#S^DKS zjB_<431t=W{7g3!I=D{3^t)+C+s8REaJ9!YN`ec>IOSjt>V~<@v&RL24Zx9&bk@d< z>~Z~Lj$KJ$QwSR};t4uYBcbaF0EgUUpnPTgKHSrW*_>;aZVo+XPY-jAxlo0y0+!dr zG^6bI5{Ckcaq$D=e-+mZfq4i~Icsakkn7<9V994(WG8z_+7AtsgviK$HBW+n}Mes*5;GgftP%1BjLOM?B%z^k$=!K!Sst7Wdw8gK4YTeDy< zmci_uL(~;JD0;JV_wSEBr=H$dTykNeWTPch;etR5KPE*N(4IG{DwzRi1wfZ+*Nj-b zuxWUAZK+1$jOBuW2#Ifl7`-u$dY+jfSs2D3r;~o+)cDxgbM|PauvTHnebOZHjfi_m zoj4=Epwy4)z(F0K?GUL?mo96JI6KL)Sj0p|8pBl$o6g>m0s9?|d5==-kW!=*toR5m z6cO3_-WUcitgB32Tjcw!F=k*mL_D4Fs^EpKe9!aJ(&^7KmrfHy?Y}2tTqmRvV-j$g zB@D92_hTN#5P7s1by2p6O(namTp43bx2v&lO|}J<&5>nZkPj1(YDstypB!jyu?TYu zuNoz$%WMb2RKP9V);>1{*upKmzx!??E0fuADKWG%#ugT?FYnUpM)piVwIHjjadX{b zs0|)+=5|SwgxsKAxE|`DM)1Vu;4t*jLJloSWyB5$_OPv zbrPVJ2n4~6Ljlg`>UXON(r(*9NvGXAWGWu6^y=cQE)k2GuU2{XB?U!<><*K5&G_?7 zYGGe!QL^4+o~ww<38+c)6EMKI|4S<6ldoAv-s{y1py;p!0}$F-1bm#U!0XPQy^B1+L7tQ#d{BoXD<7BygJ2~`=$L6Ii;&ZYb=l^K%>a5 z20;d8SqZZw-gi<}jPE}@Jq4B&TS5N#1iq>iPhu8N#U#kFpy<493%0@TuT$eK<$lhC zLJ=0@dSwHUULJmmWRhdi72&o-}P*1WA4p(M4E#aVBHpXcBHscnvln_pU%r!+J>1 z@?kYfp>|Dx0wA+xmQuDF@}yBT+7TL2+m3j(a{>J&a# z2rm-h`rhs}DW;&tCUV>beIRjgs!nHH9zp?j(_xU{s$Jtrfo!=u}I`PP~sOqCnB{5~!mHCg;hst65da z8c8aO_MMlR#}UIR(c%j37jf9?o1#F;7w)A9QTeyezQ6r@QC1FNd450q$f( zwGEt$h~7*1$f9nOpG9KO3TZNz&_})28h)H;laDeK{H{|?xn(M7$lK?Si2jEAuH|g%lRyDOHj%?GoUax5aZogWmZr?zeLF z$=}I@bjjbW4(jax)I`N>d37Qf**R;1wtC#}yrCRWWBI0x zRN2sKq1vGY4@pc+y!BYJhL)=p`CVEAkwsr9C^#2u>U<4l2l^xjeWrn3PwFsqidh=z z=~t$cvXN_v79Frn;88?DHS6r`?8NAOBJru(Ugi->o!CAHMGkK-3J0ko5g{{+;hK3S z5LW}y=r)IJ()Ev6Hq<~ zsYZC?4yZ7KC}s>~#8_0K@>8&!`b3yl0q$fa2>LepmKkXs)s!2l0ZVt?Z$QwpOd1YI_m0(T+sLE6|I}b%4 zC)60>d=NrqQCLEBIO_ivXj|I5#S>1>#_rR#ZrR~0g4=iz7kyp zaJU#a!_35>m92RR@<4ZR0HEB?fmNy~U_w@~zynuj)96*AFXII@=0b-PrX~T}2}MF% z*aZoNL;^WVNVfp!>jO`wpT{aMx$90UZ!v_BdkW+s-mc>V-|NzViyTiTL-;27TojST zrJqk7y8WTqayTFvtrwNC%(;kN0AWnfKJfauUxhH@i)Nsv27(f@Mw&(pcz&Syt_IX> z2LVaEvI1Ig7xH=3*HO`mEJ7Rt1xs=-AIlm|F-DWafmRDyf_S!&4I;p3Xzs2v<5%Mn zsMPwJ$VVr5qYZt`llecU&I7LJ{q6r>36*Fl;v7mulE{`sDJ!E=GP26ds>mv$p@lM% zogz{;QASpUvX9J=lsy_Kr2fyV-#Pc=?{OaYea_GNem|f0xUSc_oI*$MM((J_AO0xr1BtHf;8jDD7_c65j1aP9#mz|8nCNrhzYY$p z6`dvcODh9LmdPst5-cUiR}w_QWowC<1gG~r8a_z_zL|(zQTZy>{JaxD^VtxqqtIiJ zzZ($jjrzc&!jI9Ogv!po#`;A#RI@1A6;g(8>An5LJT{&}j{I>aj5;Fn5kB7e&{!?d ze1dd*SFfN4mdRge^J~Mn(U6PBmdXrNpy!>HJW@MeUKXPr=|}{%5y44D#?S1>6!>zs zi_VB0>u`8{4@u}j|8b+&L+aZr{~MMtP*PB)TvBwO^H5#%1eiRIk^0V}Fb=lm+A;(|(+Ra4QbIZADnuNQH>687>9?Is4 zAqHvhJJvRFlGw8lJ4iG_O;x!D$LY_|KtcMGg8#v^Mm;4z4d^1nVX@lc{TnPHa&nHw zsDV%m5kyHTbgm3^L)>TmFSiCNcW_|aU#48{G9ZBd> zX>p(3KNb2uMFS8m+jE8wsDq<^WLq|9v#1`Z+1V&x0}JklfWk^2>JQ~ zn#Xf35i}$Tl1-&}Mu%L8&A0Hu zC4RwAaW;bV$ozC5-`eOe4t^23qE6ugj&lM3e$ZOy3AgnBgy6jv?9RM*_rS5mpU3l; z8a@hc+@{T5%iq&y%y2Kv3@=>C%C1cg5Y_(NQDUAzMc`7sB!Z)bQZ#D?u!LME)WAXL zs>b$5odz=RRO~Ooe$>}>6f}4eufxbJvsO)*)7EuyPga$fAo7nA3?|X{yw(JcN%sq~ zm8(h8k{yJ6K6%|EKB=XCGZR0K=Mtp#hJ?&wBqdo+?C}{Sd;8D47{4+1MDpyPL+h8K zkEU_w+cqLvVA02iBR)i1?a-K5eyBTulo7iNd)68X)TU=&(rO7pM0po8`-3n>+`Hn( zM^J6I{v!%4G`IrlK?p=zj-0)pBAr@CsN^uF91+@))vS}PzG0s}%`sxuS4iF*T{OR` z-i+A+VL(&ycsYo48^j}Y#39cycm8qqfl(b{Fsmk>oB!N`znaobXoSBRV(Iu^bVuN6 z1_UwV3y~92kR~w$fvshA=a){cVjLEyP~tt&aY7` z&|_oPQHJ*=IqrJusM~K1JLB8j+v-}y>*cUeQlIMRY@X@%6-0Rzbte^|(Mo+C2G!N8 z`TerSi(SD;UtNnA6m4?(;l+~4KmesK?=qGVtq?yJSkmm9dKYXaO`8}|@~z?DBm;q# zqb?|^LF~nIc^^K0OxZZA@a@}BZUTiujvL$~bDy44rMJ!I_!ix)Vt~7QLYl2s$^07$ z{238qVUSSF>ZwJAyGt$#YAQE@r{WSldU5`w<5bFWl1p64^V9!B@km(M^ft zXoyl$Ng?NbAX)4d`?QT{-r=;;(=M{T>#Sl^Z8nU0!q}!dt0dv#@7BX|oQQ2gM^7@=gQWR_3D=kPB7X#vbkRx)KkGwvjp zsw#AoR>fb)qkWe;56LR^OX# z7NDmXNS4Kp2d|=)t1Dk?lwJsHjavy|!{nq*NUO*v{i)xy zKm!$UhbtK2k3Q^)`bP}NN{V<+5`N|i5~qbLj&}0v#uNyQELOcAetIOy6E4jm$R-s3 zi6@3^G+|e~zZ0D0&n;3*sR1$H?fGDLoVca<0_i_4l6rqP&D$f@ijYVh zmZ#6>P2$kRymR;t3R}hvwEJ>##qTkRFOg?SXzkly{kkJY5s#7nqR)MvpIx*J=Tov4%^7!4x6 z6;^5;*po4{URynOWRIZsc$9~@P~5GlH&zK>3G+zJ37a2sfm)h{>l zPth>B|Ku+>v3FW=^FS|Yt6OpdpieHq7$nycH3mTxY7{P~d_51cBiF8V zZr=A9)qYkPI78)SZzYFugCtE(riTyvO)XYHlpj^=q(iy8`xss<-`(5WrfMa>FL-#n z-+R)0CY4j5I?sr|-jgC3h4je7)zrF@fQ+p9;KRk}t+BW|Pxmi)e$!NPOL>cVzX%fR zc4yo|;8_l=la?1_WjE3;B;ESpG?ujB;=`+7e9a` z7baMnwwgJ2Zq>cF3582oGcf^MB%+AbrBG1dZ}`~%my~VYfl1{)q5XUXeb3BDF&k0R zkKQ(88};&ehQCRV%poOmOWJ}VEwy6|458c{g$5^-yhqELdI{BrZzC9Cr7vUU*_(?Ieuj!(wN?i>pwYv3C*J zFG#LPJ^QI5vg|%<%Izb;Am6OL-yEO^k$N3aA?vJ6ddUrEKe!cF(u${=Q`4Gm>1Syf zQM~2?E)1YZ8Q>V{i=uJ#P=CnBPzE@qEto%lJ&5^1%Oj{vu2GLTXTLb^(LgTxFH7hQ z9@%cHNI!RuX3Zx5E9*|aDtj{07ji+yt~Fd1lhtOX_Gl{B@qV}CzS0*)-Z0~mZT1ni z(G@N~{5N;$HM;byKcEcZ#XF-`lNI~)r;l0b#`2#zeX9AzggVQ#v+gA3aGem!w|9JD zW5=nKUi5SgKuNMdyTo>WaA1PXi9?(|hd6C-9`Te`}%^>LO;9vuqCW>LWIw+w*)fx_sk=;`D{@neRJ4M`( ztOyiK^?}QgsC0VijldsxXEnMfaryA8L)ITWlr;IGl>|yLl0p z&aq?1K%nZ1N)w)U|JaTC!!`k8L{3MD&Jw+F_emw)P%tnlh5S9>Y*JnaelE2iF+#Lp zS%0`4!lD+UEpvXTcNlNk)~yLluC7}*C@Q_Xc^lnJzf${1v~W65uLt(oHT zhL~{#a#GjpqQESg-fG9ro$3T~pbj&H=tW8?^stP^plp^=6DF^5BwobWE>tdnmeUkd zggsihv?++(LV%2gE=YGf^273i{vC)WiDuz#VFGY6df%RUUw|&YmdL43!4|z-3Wo0m zNGBdeaC3re7sgwSlXzp+*DD}zGR->CAIGyOSg~)HH+sUzgg`d$D^@74co1dzw&SC0 zztueM`}LUdk&4eR?Z3K2tkQ9eP+Q#QaSumFkMMejjvI~57&O9k>tpw!3Fb+T$11eX zS$}$-XQ@G^OsXmc`>5wOTb$y4io27j?KY~ze>UpT68ZB0?9R)>-Jt`2UBTkkP zG>TQA)T+M*Po`Ug-tm$+l$t5$M8wHexcjeeCr_Sy{Ue(4=13J;24N$47^wDx;U!U0x2~I1d*SxuuEVJ$<)O+iah$0g% zLE$mHi}yo}xaAI=Vusb5WI65ajwsrMGq)>-=rn6~?Jzd=F-Kl-YfDQa5E>Vy^OpkE z!kXwIZ3W5X@d&&p;Ud54ST%Ovb5^BC%pLCS=87LUL6V>9#FQ}A$jkcz`Tkp-O{T*= z20r$pBia;sZgKgW5o5-Vy$;)Q6&Ss!tgr8fOwOT>k6kg@7_52B&2E;o_rQT`bSuT~ zO4U?OM%m*frz^I~|tZS3eD`H`Iv=@wh;r+GULOBiN>}OLnEJh zOrM@b%yaRNK3w5j;^OX5eH+CdNKDM)%4vX5_IzeJKK`G#M}E-8Sv#TJrAtb^W3&yym--V7yH-y zC-u$i`#)cI0LLsoQ32QWSm`_Pn=Q!Xo+9pyz8pNM>! z!CQ3eUk*N>R)v|?`#mS*+xs-{rjL#=v?-R>=I?Ah55C6h`*eFoXO2?5s@%RubVx|a3ixJT%o&b>&X$pv+Y{&>{y&#%-guXQKD zQeTg`bMvN75#rSAPp-b4$LN$SEkp=1=lmbZtle6*%(^kg#({FD`e7HH}!e>__tEU&d?8fB~3NB3dNGjdI; zhkIEu^`yWpxim_e2q}JN?JDFv zj2QOBW%RLAr!u+vqvPTxck-AvW+uy}79r=bk{JM)>`c9yxc-Ba;Przy3c~Q;IenBX zmLg){;>D-kcAK8Q@Tt!+t~-qrU$LQeSh!1S3>gHoKPE151MdIqk^LXPG&v9YnU z)JN`lxBCGCl=R<;!?&4rY}3?p7QmK}hERA#g+5JnbP6Q69hhJFJvkS>xSb8XdR-U4 zJhx=ioxkD4=Jz8Usr#El*?qy*daZl3AnY_IP zJKy5({(C9I20{HKMgt(cgX^TlH^Di_m{{Hh_ASL3p7^=Li!&)Ro^x-it^sP${&U5T-wYX5*$-yJbfFo@wfqbM@)jR&!v*EI3%S4oN=CJXPmJT|9 ziAx)wcw0gIxlu`XjLWS6L}%CIM`%b%YPRCV`DI2=nI##Bv_Pe>4Y0y!&5rA%#-6vf zau4WP*}HFFv0w)-oy{d~aeu2B(gTHas z-94)>9eKJ22vSkNr#3lV^tu=^h75s~A_$CKCfWvGe!X3qsx;poJyM;Xx2h)iSn1Uc zVqN7Iak!EFy2<_}gCcm+p7|Aoi$?(`yE=EYt83{0oTT zsLG^OOq)laNrrud)nJlF>+E@#IFGB&?X0aKG)p64#8~ zX&6U|nXB(+M1HB(mCcFKv>eBVsuV48V7hj&^$$;f`J~I!?3A2j5o@KQk+a$QF7*>e6 zu&}V$nHHAx;_=uWd2Z%m!|lLEC){gbKjJMDr?~kw+37-|1ymmrVO|_p{X9I%)i}qKB z-rYaqFGQ;{2NGXJVDtNl;bVpc_V@eEl~D}|>zc+4lNeT+iVmeQ0L4$*a@xPagf0^Cd0DSXRd{pQv)EX?F6^S1 z_e)U^Wp_v=eOs7Z;biDAB(#p2~Y`_zh<==q@hjX0rk|(BSdVnS(vDB=9V- zY)Hj-p>MzigjXa1=hDd$;0MxTu*zz+o+C##z1efat-yjdk#TAYSkZ)*b&SlJ#f2)e zF{*&TCylzwfO86-0=SvL*kLQzKBF?MYpgv(Olpw+vWxiG$~HG4cC2qYRF?~NCX#Q| zS&S1n;&7=efk5-0Gt>zo132*@S{-)T)eCN2vu(4wQ3xtKKEX&L!VpoTz`&_w>yha! z0!+ErkiRAO+)#V3>0n5fiE=bUYWx)0C#83_4Le9wZN`_IS~R^n-~a*kR)E|E|dj$r?*p;KsJ6RV8lvA7VlLe` zBQ3P^7_IWLSK@|1I$coHKhVar=ZWgK=g(WNZP|BBmwPcu84qUNG3cs0)pyLAG3~1A zoZ|g<{M%t-hJSj&s~Um~Zhzk%AKx0~n(=i3#t7O?`^=Oy`%}-wy@*+Cz`eLgE>mxf z1YWnX^YAUPK(ax72Qk$N^3G=&rE3%HX(J8u@uYp)srKZ<$3L3K30t2t@Q zOgpfqw1qsvmLrGP(OLFd&iXTdp3IE%zH^BQPG9QH=6y|BYi$z49F)Ik_G%}5ao@^d zm?ob_ze#V0>Hv|v+w#)r?m{M*kL?M!0cSf?kjF<$-p zMypV4xkPcrW5f4xF^fMNtGzZY-&jXy#QKQvaK|+C-X7q~#r@NK+>yXgqZ6IogzZk$ z;Q$U&@WUH1vmYL6{wVJH*Jq|LI;*SH`>X1Nf9LWlRnM-Kt+Su!=i5HYYInEv9~1-q zJ+=OFOzo0gLW?d@RFv}jx(w9U>hZMOka=s&+i3Rr#8 zz9~IL$v|)OCc2B&V9KiZ*;&fnUZ8QyT{PUNR@r-W^5p0l$R5tiemCzTL9iJC!v^&br;w`oRqDfOZaTK-mvxmI3r=S2f0u%+qLixeS4u_s?XN z_{;iL`aL{1JNfQ&62-kTm9oh2fEF&ppla&s8X33$p;TXGa?@!g&+GN15;2QAS{QR- z%5}HCN_MRVM#N13lJ!!g1$~P?b&n7gi*tW*+_|kkf;iNNT!~Uk5-(~e%qAr z&gv#+ck4vV(7JBXdzz(xr9;UMiKQ;eXprGI`1m%Z+M_d1VkD_|YsVBq>Cs&Zdmu7Z z)n=-J24O9j1<_u@vS|~fXA)dIb*QpqJRs|u3Bm-r$siZIkNBFrH}!0&re-xn)3jks z$Dpt4bQNV~Wwrr+Rb4XtHPpIhw(IUvAB4eY(g`5QdQ%@n`b89ncHju>b><5b{Teg~ z9d^Rmyvn=T@$j&!?&B_wFP(Fsvd5lxPfNdjD|!ffU-0f-l9yw5>odvJqjq2cVtP`D zWG42S{^-Iet{bTVHo)vbqzTzC(C;Mc9L!5N02?rAcJz7Dn+rHtS@z zV{6Aus(^^(#y^7stJ1vnBgW>ZM?9TO+}565qBLjdHWfl}WTbt#_xowB8K|m%B(KlN zY10jUce3c)cj2Tuo*$hyyu4s*`07d~r`)+KPhIMvvnYN@RC_&7FY`+GdV6LWRI$AR zL;6SW-mt;(c>Rub0&3hpEHFnY(lBIFtWN5!1Ksa*s~WqzYh^{dabd>`kF<=8dsbN3 zVr7_qb9eJ0s|_#Tz^${{=dZZf*lUN&Cm(|FY#$bMP(5+iUn^&>);rOxJE^;DkVFfO zX{CE*jFj2ow08sRzqD6XtUmDfo}?!6l}j!~jk?wBwqP#7$?wsaHS>9ZyiCB~^SfeP z4~>$aaZ&Y9Cwczpm6baM3g9#Z=+h$#22JH5ufqD){&P#N9%GV?jppfIG`+XGC9C)7 z(PO@$)6}W28u)!E_PZ(y$zGR8Vp&H!6Zz2F$EWZi(17u~*JlyqgYAB^?imxp_V=pL z%+|}G+Pl3QXh20-Qz60s_ingk_4_eK*Z=EZKo#8{El|<1>i@Tpye@Hp1&>1mu z%Xe?mxI|Uuwv9VFWcSLSlN{N0w(WOcQvMn9pBCWx#Q=TnaG8c)Y?)BDP-Y;!%$R5} zf9hJ9pKz7UncjWnb-n6+=iv<+wtJ{crw`!Rv{P>XW&zbd4;Y-P0EAV3R&}GG>i8w- zIF&0wZ{NI8vl-hg?(PUpck!2kJBmyi>!*xqWF5obkn>E@3{G^oks1u#7iOaVsA zpE@+1{&mFk3pHgI`rmL^G~&m*dqERu=&prnwGj`vNKTNIB*-Di(!E9w@bd4ijs50} zk6h(@F%vp~M9=WR3Y4!oC|t5Mh4sgK>=g`ol-%$M=SOcUbD5t%5qMz0SK zI!J0R#ql*RJ(qcgat|5{$|p7mG5j#G%5?lG6_hyEU^1@RNK1On&tC=2AtVd@6f*6x z2XAO7JMJ=P%2Zf8kx`1~h$L^)1n5soy>otS6fnBp9sc2v1KlKmjGFfqA1s3?Hu2<)1i zFjxZu&iZi)7h60vhcNrXdr?k!1*#q&Iy>jY!nY&Eql-z~;O}9hM!mI+5>k-oqV=G> zwDd9~Wef0{prvaesm=fhGA{YZ@Bsr>T?)#rsjlch{||VoJl21$3JKJNN*nT+>X7!G zPk#CN^Igy8KRrcy_McLaR5hFXNHtx%q~D@+5;5GF=d^L6>=V5uH$<;N!0n+hQmX40 zkPek!T5e}VrjgrOf|FvFJ#6i4PiY`~R!9^&GC_Wr1K3Gro~?iP%DLipiVR! zG54= zwt9C|t0Tv_oJ8V2|2Y}gcYhkdq;y`;l^K1v4mYbfYZ%o3oKm#L&(TkN9Qm|_IcOZR z>zI!vkzulqNaK<5M}+SJmjzN`PvN---X2*C%{4CR7szz=@P?oFARpv_7nLXqu|Ztl zlHx3WM=37R7nU*vSmr7U;r=ezGGPYd^&{HlQ1BD&wrt*o7JKvfH-B7YXQ?NULXk)zyhzZQ_?W6Y&8|`^=8PUr6mQc zXI)=gsH5@T$q{{=>Uj@^onaj$%J<4>YqK!CrGFO0c~PO`IOBPW$)-CSJ9J+u>WKMH zCAb45=DT4Ic~*rmSK9m5ku?f2`^NHC$KMn9Led>ptoQ?iKWv$USwmC@iB~MgrOn(k zt8mBGr5!9R#^3hnp&(t=xnNmc0SA+*z%l-P8Yk?oFBf+BGoqPXXdpLq^8T+iw0LZ zVd}d|^pxV9xfiBs`@Owc>#T!=0v2*JC@VNhhh}YYZb|FWRf&znIuRGI6aa`1!jR!Swtk(%^^Ng~t$fmw69rhX&!>1USSh+MQ^4g1z8gM@% zj1f-?4%Ye6W^LLGydBfObzAxmdOMj3I^ene=8-g{MCF=_Te#xu%WKfQb9QPfuNt7c zVD4P?X3b)qK60!zd{7RtA)~sk*gfgJIA^JsL(^)jpRGsgT-LbYls}?~F1?=NnVdD9 z?_wV@Db3$v7kugBg@NQ7~~|jX*@JypP)$;B!m$__g~El4bQ_Ihc~Hps?}$kM>Xj>N>xF$ zW~9mSq2ur-ruo|au>jj5Vmjf{KdaR3rn*o2PEidNrcRKC*Lyq~iEB!9_d2%4!w zd;-<1vVO;K165o;UGn>7rj2FE?dOMXvRw#eIT*v31(E zkG*l_hQe;stIEJW*q=lU3;dBVX*a#OWbCS3F^|>Fc(ie&v6Um^3W^ho#lj}}FK`qI z3A<>++jQ^l{9x~Tj3go_0P4A3ERo&<_R#tim5Hd8Nxv4Q4wEPAgR(VUYP3Q8i=f%_ zKW&amIA)*K!K|vaXMI^c93#Y@N+-#9gN72(2U%6ZkhTq)MINDfQ*aV)1^s|TbmzWL z?s;Gs7Q<-@J;g&r%js2|(>_0W9Gi0CDsJLa=vdC7)a9VFiSee*n`PMbHIPhs#U5*q zgAg8RtU$q>OXF}Y^(W&U7A}KIpAORik4mUU+9GanMn>HJ{1%2buqRO5t>Tb1Yt+i* zY<=S7;Bbi2+C^BAl<;3T%7{pGzxFGRyQKV~n?K-rTl#17t2Yb8;e5HesFB z^I&ele7C2Re8soFA~#7#_PqE;@grx+(yYH~9fMT!_B%I(`0bpwGO{z06(LeT@!azl z*fqxsdPl)j#_cW%-(!M6XqHsrut;}XDR5vFjFHcKawXi(Qv4UR;x7Z-{U;M9w0nS7;JVo&s+_~t}(J#)KE9Rg+S6A$?@b#=W9%YfWb3OJ~Enf{` zQD+K6H*r$t*r-;isPNk#v%M_&iF?#qX+-BoOj$EItvCbf8 zI0yDQuUATa86IUneE77r=3jo{WjXR-#kI`LV?5#9MEgXihd|1=*Ru-39|rvX(ditq zoRQ(-KliM(nl5JBnWK1OdWZ&AR&5Ol4nD>#gJawy+8_C?Z(hH?ntG4DH7xavsSYoT zKjk>e#pG-#?D|x;yyK6C9(*Nyu~kRpHtKRIA_8 zl2yAbmu+kbFmGpPcVk^#Oz@}is0vN|e*ZXp|GRLr0y|=vZ_{gxi#C1vCvZ0&jK?QX z*y$%?l71r27sbPI{<~rIQSiOBn4ui<-e~C#S=XpZU7ZfrGnuq1H9VXylB0cY>Zi94 z!bx|A^$tp?kF_u|4ix4z8q6~r8VW<7*L zL$_x&V5B=EZqjul3CW}o!gL=3=q{)>2$J!pl!FkXkTJDsf8MXx3}`++zenr|o|=1g z)lWr)O_t>MaUF)*8eXOlir%_aWzUcih%d$;S@EDg?xbUw3PFU8cb1M)U?94ln>!HX z+N-3%8aZb2(|sndIXT>VYwx+9xAO#`r#rea{@g(v$|8A^5#$Wj#zk=>rX`aroF@6p zaS>t?j?4-pH+H{xM!NF}V&4rr)|ZGI?V{<}^ ztmIJC^Db8aDH-7P8{AYj*8vJV`3OvW!TxCnjpW&?(N%6y#B#V>P0T=n9SDN6r8p(Q#jTU zuZg#jtqphC_ZYGr7E@iM5GpDvNo8qY_=U=?_nx16puDV1d8%Ss>uKOE!j@kFZ|0!7 ziUfs$?G--Dh8ct!3@fnt0Q;UD!_vzL%D1`U|n#OHd@c zeoOlN>8&>m0Yh$Aa%gnZ9KTK$%$2!(IsWE%=v$eb+4WHyPc!HUvT850BxOi?(c8Cm z6{Nt>kVSFosaaZR>G$_m?T~cOT~h&b-ctl(v~?b2-{u#r98m;PqjaX6ue+(^-nI5u zC>IJi{5e+p!f;hli`_fHdslk~mmeKDju8~b^BwH7#du8-RaXILbm+m9!()e^X0NxQ zjg9V!Qwwx%>oZQ~)Av7@f!guAK8WR@s`Ic=l0l!KwDrr5UsHp{(T6ZaGB?n zD#3>oZbOC+wPxju6I6VOh(p&fz3i}dpu*;nKV^Etk*_*gpCG6Ei-8UvpzeTs3wl5S zeVcSGptWg-`m^Z00iUn_dDGlu=M)b_0MoUDs7$9&Q_y49kL9A24B7M(1kDKF4N8-l zK7`EG!Su2Rf2U(>4gZ;#Rj*U4-L~22U?jR|WI^=y?a5utQq-T=FCB{X)%%M|d3m|L z@8?QESwB)Q`+PB}lXY$E_I_|aMsFg+`#wB6If@14qZD)h_R+O02@kX)fm^Rc1RI>F zOlO&2<9HK6nc1j&zK+k`Zp-QoK7nD+9oetAghW>daXkfO%FVwLCf#`L!I9Eb#e~Gf zxP+W)L-+NJ8(-oH2xe%6u1ClRz*UK}s4yGyz!GIb7lM#42PbXJ*)4Mu(V9kUw@=%W zc!-L*nGDKyvG6{9?3gBUt?An{fyYhWwRgkKNw`q!@r#+zquVOGw(gs{(%uFY#G=Bv zv(E?AwBph4b^9fK`Mr$Y?B+&v$ivPY1skAJOX*(ZV>kN6$M@*;LRPP~HsbEfixN^z z3G$u`LA2Vt?$&RYO(vCi9vmjYl_5B3B^#pI_$Z)0+&GM`IBO@%D zqnO#ZRD)*`)%CJU=d+g}rU^y)PeU#)I%^s6(?n5O<{($uM~cl2Fy zB>(GV)3sq;G1u;X^6Xj1Mfx9E(Pic3NUV(7wL8IL%8mJllPcJzImsiBGE9f7D1chJ zr~fG*82h*7QU|lRi*Z!IYGu&**_fNyht+NwGOOf#v=WOy~NM$gk14)z)q+ld2sXNsTQ zqmNun+er1=G^B05H|URx=8>7K-#`nRrkg;P-~6ywO=rl=hK8-n%?C_%m;T3GZhY_| z!=*hDz^sRwG$wKb-xlIqJoMlMjetq)E?_(lBA?aDfo4&iU9+kjJIo@Z%q-&9v53(Q z4hBiYZe@!U6V<87O|xFT&O})DFgbAk(LWq+NuK|xCfwgJEb$Wsm#MLF7*8XH`cZXd z1FFnVEa~Z@#7RA9t6O4WwQZcC0mruJC$c0S+f|{wSiX(<%17zxd(54QJ&xpskj{RRrm+M?#yEr^Vc>=G;!J zs7aU;wRuc=*KFvHx-zYbif`77^L^+va+jVmdiK4n*d8DI6_{sA^CZ^lI*q>0lk_|Q zO1eXcsIm|tI~@;xz1Z`lME}KEwd5CNA*{*ClPMM@z*nNtPFy}d$xKGe@FV{Rr4A~% ztv+X(>FS1%cE#kNMv@W4NlQxj^N22~HbWqFsI^FMsYA#X-13!Y&nA4E6pLAFIRRwcJ3y&5wM=v@&Cpg~VLq0atuoXY z59Vyk$%Z;An7zX+gwutMlOhg={T^eN-(M)B4>w>y{+q{!=&o+9m76nBulp>Akc@II zPTkZ7*?N*rsjnXe*K&Dg>33RhwP#1^+a(7_rV~GXy4|mRW76Y!7NE@SjlV(yQ*7>~ zAV!vc@?BrU(o!#OB2V2Ttx?>!Yu8Ty!5|u3JlU)9d2D{_I{N&}f#XD;&If(XpCOiF z{#Ilkji{wi5bmV_kNFXI%yLDI3=fAR7N?0QP+$p%8tP4&zCw#+tg4c@3P)iE>}LwbU-&%&WdavXSzQG2Ox@MeuzMZ=Eh}Kr+78b zb$ZGQiB&=Ob%|n#H!msW$s>{-#9<_}j1-t392373W@Q@Kes0^oeFJH!slE6VVLaP0 zTPNJwK75{TkgQMYNwOmm{EL{Tdv{NN0 z*3!YpHXJ<(7J!zbpL3krpnoS;($Akihov4wUWEBj<3uioeoCZkv`0w7l8)u`kOZvc z|HPa=x= zVyJA^-51dk``$UcY0U8P<6B5P;G$(9AXr9{?zfLd#~<6lG6LLzCqE}Y^I_EI<%VGq zMG!bUOI{;~@u^UT+a*S;x!^;5*?LWU!p9FDez=8qc|}Difgq9{%)|3Qq)fRpXx%au zQj)Y#Z?C4hY_wn7q%|pvk_XP$mC^>UOSERNu@)_?TFz@bte6*8HMHi?!G-W1Fdc7>xO#g6rmqdVa#8Yru3flvedtbeuO$U0YVT)Fbok)*j?AlU0 z$iKIKZV#sxlz^GAb2@K!Y~5Nw{}Foh=mOpGcC}AhgFjc|ep#+wm`P>s73idB1tc6& zXe7?}5Cmbq{v2Wc$~rna2Il6+Z9BK(9wqrM*qI!o5g4>Wt~9PbOMm3_IcDa@(VR#U zQICQDaQ>Y(tWSJ4O;Pz~VIzx=Qh+G|%F)P{`8CgG3c|+Z#7Sgind&KUN19OcVp-sYX zE_v%Qg+pa3I7an>c#?&`H{kPfZ(ac|idx^=G8x3qAZ8>+YkJ1L9;0*(U1rc&q zpIli=-RyNmaxSy*_@2YAOJeKhCMujxPs$3_LF-?8kmIOk+cqt=!%BGc_U+g zBk+=lKM-4V%2S_&SbO(eKTxj_RDj$Q1%G6hKX=kV>_Rq=l5WR%rNkOC^v zp>0QxxPJTgASWl8vF$QX&Dz)wcvK$an%Nr;UnE2Leb0{^rk+VnWthmafo3Dr-KR`h z1-GIG#~XCv!V2ASF5Q3bqhuDbhhmla8Ymi-8QP@q6aYH@8!~w-@9^jYjZwv}rhZDm zS10mW_~Lg@Y8j~*EDGw7A+1Mfs*!b;g$+*f#}%u1lKg#xY)ldcG0edBRbMG|0}YZp zP>4zj!JFH=B0&_~Q8P?^@XJ59ZZ+Z> zOSY(GH7b+nX~aq>YN1LH2;EL!p?TU@p$blNPYK^X{BWZtqjysNzv78rWh07hSSAEw zn@G-_-Br`nprof{YYb!RU-u^2k|9{9~r3PvO@sU+JEZMYRFhA;n#Rbf{u|! zB4LuU;v{?wMhpUxyAf+;E8+fJugWU8X2j8Lqz0 z8)rx}=d~7Birn!Q7A>Fz0A93Cd9ZTYYkMzQ5{h}!q;X{JepT~Ohwe>C(6F2Oh9M4s zIQ4m?2>QLQL?OU(KK|Wy-rg~x;T;I8mL^|`#2Ha!N#825w+I8KfE!A{Vz^D%_*~i^ z$%mnV5M?a~jrg*O130A?l{M_YM^+jS(JUii0IIThBDK?Ho}8#h=WvNlWey4;0T{>^ z;{3~ot_yg{hHHn{OiYpBz7m$6-1Fd=jX;|+u>%zuYM3c&>ljDW8L3$uzh{pEU?V|E zBV$Pv`V*&TT}dV1wX5YB^xzVJY*2;_E_ltL&mTrE{$KDPr?A{1f=GaMCHG9p=L0@S zan+C$tfu-;`ZqM9m}YVt%>}YoAxAwE5of*l8LJHA*J1>bXdhI*d+{-P`S{p?Qc1S> z>$tKa*mZTnl%#su&Iv0qFsTdsqGhXjlkg*!E;D06( z-m$SRP=)EZ6Uq&nnqHF7(v^RfOA;0v^%`}%V9Uff)d3|7MW~g0>oDKIrwdLZAYpV? ztFRY~_*Sp$G!;3031;N<6)(|FgJ6S*P28}Y(S5ud1R(LCAnugf3081qkt5c;)$azj zt4a#5xELXYIJQ6M)aEhkNh1QsT?;GM@ID1133_cTe)oYtr975=4L3jZ=Q{`Nt1K)i za4v(6C1EYlRRIP)PV;Uf@dd!WSNWv$#F=PPrp%pt z$g>G8*Z)q(oV8>DNDYMVu8?&nze!~601s2(q6DxLoDXF3Qf_Wa_M*aDasBlr`YtrI zK}dw77TSQT2!^9$V(KBM{kyl90tXbR-oE4!ZJcd6O=Z+YmqoekVLszi&JzGz(9Hn{nmMhX2^{L(@Dnnq3?LW4Gs_H*6>CJZnr zq-*C{;FrCeojvGw-CMlJR|I-0{gFh7)k4O~p&B@h=IC$5U!wpRM|=kda}se zs(I(4V^*x9-^0fj$&-uc^b)uBvTp4VT-Bo^+1+G$Sjde?rcAK8?B_C-<1erc>}Xq> z_)~FPPo8`+V*MHe6OF&-bYp?qQ?edMYE*@FPs|sB!t!TMrPi5sf1fHFB$Sd41Yk_w ze(m7SJkTNo!fC z{MoI!5BgV?)RhY!xrL5ASg;hU?biNi{(ipsOM3GG_s&hGY;&IL@_7aUNg^^!zGYw) zja%7~eO>|@kosUTKn{TkZCaeLI}JC5r|G2H`UnG)R^YCu=00)i-hCW}Csx7YOhXBE zkX0QWy$UpftR|VPVDzOuWHwOyB@Q`-PPjA0#4FA?`B-!rYbc=-{}w}#V;`Mn4$k>3*>U2!a~Wf#vllb)PVL)w8pG%2)4qeKr7mlX``IEhWpSw+2VGjd`6>fRwaLr|~m!7q&g#z*^C^euvHg7ILPRMVX4p4nr==Rr$ues}BY?c0qp6~wP@5Ll_;@k+^D@=mK+vjdy;Y}bMt z&tGLulE_ricB~$di5v7-C;K+90A*~oAXJ-$^&Y0Z+_+6rOnhQuqC-Jz?vG=8Y9=Vh zw{2VhU~O74LtC4|BXq)BBc}osk3NJ!CUw08;KdVV0zKPTlxm<#xL-!)&1lkNC(M&1 ztP{&)DgYp9Wr|faD@Z{kT$ZD9W%v2(|2q~9l3Q?(N^61y@CwDagzkSr&rX+`jgIR$ zSDHjPqNByF6aw*-UJ-)<742mm<1#~O)(Ew%3W{1CY><5Q#f#m3&DxtZJLnw2I+q}w z_=3Hs#_gxtk*x$K4qTfi26OKq4dC*;ryVt|A2>7BhcitXGjwvyD6@P9HbN& zcG$z+U5RJN7$HW7xXstH@5Md+n;Ber+WbZAfG<{C5qBJp-OPm0gWs$G4T_W(M+7hV z7C__HR6EGI3+JP-eKYRtUMI>#qyr4lPzJz|a8Q8=V3?(W!c<&48kSH5ow=C}%D+7C zOVr!8Cab8*7A~XCH}$#opm za(7W@s?u9`!6ZYGxaHs<0LFzMNiL8B9v|X*$-S@`7(RX!ZD9LPnoay+aSa*XoY@nX z#Vh&?&E?mvTK@ev-RZ!Se^e8;%XN*y*sy2M(>BlM0es8QPO3gSqR88xop%eh#|of| zd&T`Z?5lm#BZHck;^kGPWtoadj9;tP(M~hi399rp8w$n7V1yLZdiFXCuiq!a1#mF; ze1Bm1#LSko325x&m$V3UsMGV|40Bd08RKr!!WV?YuQ^3E(k%(|NU4_d*+IyC%y|7rCv40muEgDkqYcUVH!_3KHQ z{*4;7P%{ksFkIenp~ILnB&)DFrDvq* zspFwe#l5pjksOgiZv$>A?7nOSViFQ#q=8N8^f|p?kkdHt2UL|-{ak3>9Hou~I|*I} zqa~R!d3yH$^+%5ONN9yxzI$|Xe@YygEAyDVYIG;7|D8&)wd-^>5wLS&3O@}v@AJ7! zc2TB5SDS$YrKabgX}~plq^ONySWY~oDInU;w7qEsuTdHqo0>Y0g(GVTWlpE9v$VV* z)F(drrn2Lo>$h&{hV_kT*l(K1Arns*s8_QgB~gd>Vs_>^jI+|cFmhzSeg7W+ze#)ZFH|lb z`jNd|d^*&?YK)!-WxO>g0`}zSZQDAWo#ZqLb#MDm(JO#3S00;(a8yZaYgZ+WZM_V& z*J|0`YHQXykmtS`@kG5phgJ z)h(HujPC9FESZvzt4Fkoyj0VLe2ia-{D{6~d=LU#LDd*}Tj+POJYt7}LE{v8}!yZ{$ zT38Qhb=q=po05_eO%+>!61$nrwemFhwmcQXu3fe9-WCUogTcpS2|OzyW+6=i1l=WF z!{o%yf7>!TTvaGI5zCXYAP3$0R{bJ)e=??_Hzp;nV6j

^0!BL{n;#IwD(7blxys zVx>vKajW~cs&!QWoo@*lf#OO%c0E`>@zy7D2RAoa#=iry=ycs?kgUoxGZHLyOWTr- zf>5#xb5#3AME09jczq)SSvvpYEkWwi5dsbm{_Hz}w+sJGQ_EG`(e*F)z>QSWiT(7# zV&H*oDWM)sa^aeFO!l(neZdp}_y8fT$zMKw-@%lWfpj9=(?A@7qwGHFZn&ct1n-0o zdE(KvRnQUK4^k#_z{t<*ZzL%u3bqgID5mvoV^zWs5`!I#igh(U+uAgi_=z%grx60N zd3&#>?gI9$s}SonG(R`utz{9>A&p-7Y1WA-B!}>^!~EHZ2h}9kA^hf_n<_XY9wJ&ziDwg*&znb_8{q$u}pKn z)5+Z?iVHOHX*YB84tYC56BDP0EL-R>MrEp}=dYT_*w2h}{>&?=m~ryS^SMgi-$MUrp>FsSUy`gBCi3hnmtNVxt9-edB4z)qdS-HdR^WDLYjvI1U#0)b! zyXbu&Rrrl|6CMZY4i6tc$j&arwBVIz+2ZR>;Uz+&Lr+fMHS$rWYrD4{GG!K?-Hc-v~md76L$x%T$%CALuN5$WyJ#(pz90$G?SSwLB0O>OkEGc-c^wxF3`BG z%iXifzvsCMlp(wW2ke5PR`+9aJX7UL)#+_|iQQpOdSdnI; zK6!F=hYd-6hHMPxaO%^@7ep#|OKwiid5irv@dH3QK?Pg4o4H!!!laibHE%wesG}(f z`u*jc20|8(-Y3?btf#fTuM93(Wc0e`a;mjwY73f&K^$`}pGHJRl2Kro?8@+?oHry} zY#@~t|5emmdQ59HL@J@MBh{a_);K zXFq)KbnJTjALsGoO&a<;J3B93akQ?Ik}%9#yN}0x#eKx3m$UKTS&?JzA&asRdmwa52(Y zQnUUuFQYYs1)G+6^?d*RS4WGxx~*E7P56?R(yZ0ef;uP{qXPmMzhLNN*wwQ4=bS&E zqdpjc0f1~?Ls7o#^aRtUMQ`3jMAO1FR{F39}%0x8t0t-CGE?d>~$9 zNkCNi+O@WTy;P&^8~O>%4Kp(*yQ9Hbi>)s|l_R7|?LtM3_?F` zwzSa)pLDhBp-9M{)^i8D*>X)^xD)>6eB-4sg$AakH$5&%MxJQrMc=`ok ziN&tQ`~&;to?-U!(3p;#zt3!32l;-dcN?(x-l;{s!p7_VUKM)4q}6xTrAyV804TFo zbuu!l%KPx}v?gvFD^r^P_p$52oV=3bZ|c-|)0?2Zj|x1H7qpGJy-KA zHr;SOu#m!Lxy$9CIvTalV(=k##$o^O$Kf@3o>>HJ0e**Z;c*id(Dy8T71B%~WH^e; z#VfH|UTGiaZ#dy1wf7q9u=CC?F2&t5Uzrp+QsNzW{c(|nWDqRB@S=FsgzIeTfr(B% z?#0wjahs@nU+@23Lc$nns;Eqq6)e#!tnFVPkA~ixmC2;bVxPxhy!bnGITTVDe863N53_0?3`?cTR{T-dF}I$APY6qV}rgIxP}X5PVpg-Lmy zN3XU-lM+1gz?_5>IoS*o*5usoRM^G*zi0Nq;&G@o;7OxRH`>lQqrc?}AS6pMFE6hW zTWRL62@5XhGDe)fq~v>XTt?Dye!D)KsgeSV8>;LyPmLc5kz2wWzvFvvlh%#?4ujxFJ)FbI{TEH^f{=c%m1fI(6{r)s*lBrTx z8Inqdq9TM6l_5jQkTIGhWX`O}ltco zuDa!%^S&8-6{n=rm@oGA?LcEVhMyvZ%)(_@C#f_zGB_)rZ4 z1EGiU@w|y++1{M=M)Shn&!2TZpE!h{^XB|@%OA!5oX&XdI68|cn1c#PM?HS@ZOQOJ z1Z7%`WP~);lA#{3e}0xyj$i%J*0oE%b{+VJqJ*50oSdw2{CJc8{fY@Jy-25XI zBh^(VF8yQ9{2yEGas0|M21?tR1fMexH2BvK34eRg)*2R*5lQ{%efgG7<{@ zzPSbq0YO31+vnd4{#fpb3wqo)UwyQ7T6?j&(@NjSh$*G9jo%&pIQsx?m9vP@OG_GJ zE;c?sCU8Vklh@bNM*OKcH96U<W)M=9X=^KsD5%-|+qN-S zPhED`cjY1TUgE)rKKC9QQ!YVME=~j9h$f8$3tgHU;ME7*k*ol?jefBaSRw!R?IerB z{_Ah30GIvCxC?blw3<#cZQrk3wOr^I@ULHvXD8z`)-p0sE@`KfL*I9O4ocb;0D34C zlCwHA8#br9TbQFJalUVxhRoJg%S4ZflhAixr!cLdj4$=vpnOjJ(-1 zd;(JknP^%%IwwH@nuHz(XB&W$w=g2CyttyI$B(Vvc{KYJG{2~*SRBfC*)#I~Lxg%3 z5*!yEVhcz`%fmYC+SL%(<8O)FYUSS27cXEJb)A0&ElGEdX={JV+_B`JD1%k30QI#1 zo+T8R)zUskL`pDx8)ICDB+=fm0!vGw6d4g+s^h1<04waaObmF;0;h*i6m72xD2f%e zCBhct{*{%L2?Y>wDD^tE(foi&nJizAg)DgTT7N$Pj(ZQXr0)J%juYoDBWjn$&9*~g%yBcxs zfeB7|uZT!;tu~s1q5PkA^7Oy4MZEY&1D!`{E) z$iS&x97i-X-fLOo{5?0%c5%0eR@>sW0TF8ERusQp`}z1}x7KbZ`yyXT5VBWAB%#3o9|rcz!}8Z+*-|dgiNB-+r{f zr>lAMW=D8?dEL|Cj~o%8t_MHC7nA_dBHG>=l5>{d|L2@H_=+&Tb8%Y9uoNM)kx@+j z4AkwxIpSOH-}0%zzHdI_?DY}QjY2XU8p=jsE|3vXF#yba04W^e`SM%P%R?yZG@WP% z6OgNQ(4rctqh&su21+F;KF_1gVqiKe2 z2&8e4hmrzKEFxJD<{XZflWHbN{kSpUkRzj`=dP>pnLj}yj6kjap5oxtw{N!8U>fAz z{nGuPyjQfg9$7sxJPGv=kQqZQIzadsdA@-81Yoe#7!v9>ToYnfVJQ9W<}H_$@}&9g zHetEw8M!m629+5vc?~d(7lF~SZKBa^7ishq;xU~@Z^$9pkWJ>Np#Oqm^4Qw-uWD=k z%1uZ6ZzH@z+Oe`b1W62l4XMLOMU)dV1E_EJpe7*;+E!1NB^WzS?=LSF0XgmMJ1ZO8yN?^LosDs3V3wV{N3;Av9}I-91UE`=gb#d^?uY&S#k@k~ z-y?ry-3t-Lfx26G2vyb9B#{}?@XX&ChO1u8~1R}O)duYks;{d zQR*16I5%7w|0FmY7`?N&gjX}zBqk+Qo)f$A@#Cpm5fOkT;xsUP>D>lC(A(u29djI{M8<^R$Wlmu+1!`{S%{ zBQ_{B8XnC5VS%X#|8jHt7oI7g7fvU5%aZ#;_1 zP0#hwou<-b2EB$P}6+s6Vq-ie?I`~0k*y4DC=IDeVuWjJ(%p+d>ib+V* z2jyknPNw2f#1b9fS0*ch3dje?Im~pAkh=lK?Hh!8grqf(9I4~` z+-#mr#yrl}&Q0z80`ZNTckheBVZucs8{IFC(RNLesYfDuo0K0NlXCwu*gr2Xt<5W? ziYZ1wcGtKE4o|tjd8YzT6|K#qj?s8T!w`M8wfi>Yd;Qm>5<8cbAmYD8OG^u(RD{oguM0M!Bg3`;C$fn87d{YSJL(KkaKQEjeIkOytJ5}LA!68I8DFp?<<5bzm!<+rm4-URR z=uS&XPUh&98h}@#sxdo?aja-C&#t)Vo2bk%l#}Zt<=?g=u)N2ieEkLa&DjgKVAnY? z`9Do*YdVH`M)p$C_4oWOZJR$m>S%7xZKVbz37`BQ^OzU;f+q%Z2ljA!Y(}vah6ymY z%~L8sLEs`}0xsaaz*ioUA|mO3QGNZ*3!FxI@h|IU^7PW!hl{7Tk(dae19FkpLQ8?| z+b=G$*fsuk)0<+k;o;$58T8b{V!gC8U%dQJVLuA-Yc`7n6y(6aCdNrzeD*|)AxycK zg=Hz+J9z0xsP?qF4L)*=QcFZ@kNQn|L{gZ_|6cWpwPkyNkina(`Nb-s(+CiG#dHHK zb>aqA+A3Do62Bw`)qSCSYl9B1#~@cUA6WJcRq}^bxp?mEs22wy8?Q~%C!i~4GrZ<%|7$`Ry>~I)uk(NX`Y=W|Nko(KHqJzD z1xN}906*8?Taps^woxsVkK~DYd27qd%lWr%WgY8095f|t15bwWAUwdP;Zm8HzuXn3 zJ#4$Y0v)tS)6LvB^2R?zh?b;m%FVKM`}PPe?_|RbRgJdrjQ7WDK$=C!Y})@e&fB83 z1G|wUja$K?{C{k1iHPDDk|+l6lG7S|2paKPuHcocR(;&TPw-@vNy)@0ZheJ9r;$P5R$-(B#Po8#uuJ5xq@+^Hy_ZG_53nIZ?t@PNn>JJyuxKD<})dP5%R6U0Xg%{xl;;7&f zWgW{Hj|%%k_v^?^SwKoDu~-kC15S4eKhxfE5_s&_SAHZylRy?lS=i7gCM4 zrkhG2qkZKNw|m1mB!}f#4x3t;iF>%Zn)WA6iK(fKIF6=OZ{DzvK{vP(VRWNRzZ7Gj z<|BJ2-49l>e0&c|E?@U0GTel)NL07b6z}E<1X9cki^94pn>i>ya=U;)vR$uSnsy+v z004@l0S19BhI}Kcxl&q|Y^1{laPXh6HWptwz2G*gk2}i)<7XaZ4v;sGrN6tw4X_X2 z1Jdq^x=SA;_*{lXm$bub_JHfxeT}FWLY0?;u=jG^g~D#fbwEmpG#+5V?Jh`7zqp$z z0ohDSQbaXE42HqU-2e_C_%hS<6qp20LVsoO0p+H02uYf|Zy-HGm!p&WPef4?D*_r~ zz-HGMYB_BCzq_7JJ%GBEHxHi|L(U1sL2UNcs15s3>_yzsq5T&yl1s`7$w#?~fCwTY z=b{-9J!~*voOJ9vNU5v9j>w^D1gm>jdn{e+`v^VG|KNQbz=dG(M9VJe!&s{&&Zv0o z9&IG?Ph$`^*!JyfNmRb#~23?S&I?8nq9MKt@MCF1O?N5l930I25j zYZ=bTSWpiTgN(WlgIwi#(B;TBCP%dMgou;$b(E}}obqS_8!=w=t$DU-EEuUhU}B}& z#ZrstdhHn803wTWpxep@3-OJ6_RxA+WJ&(&V?nuxyEAeh$VMUmXOkc<)NnPhaiot$ z$uZgh(Hccj10_yVw7jgWG8`yTrSiEIW&dO6Ok9OAA_}D|Z=QxE2)&~Wiz0oQS_RbDp(@dMn6IlroKPAy*CD3yM9N&`?&rpaHw z?)XDkOFxX+LnVylW*)#C&YgQy-_M(qY(XlrFju-kH2`DLQ)0U$pv7w={t)UD`HJ;_ zB7dZ)%fM}$M`85R2o#B`L2l!)B(NcdTCF?U*$)!o>}as(iC3YUQ1Rr-r2RC7k?;(h2acQ{)(7R zX*4IpcCX0ewl{nNbAx&{MC3nD#h*_pZ{TskNKfGQ9DAKFbFEqDR&qIiya80~#v!7d z59bo~v4v3o-@NgCb;`Ewu?9ccpreO=pa+?>FY|sy3~Q_Pvm}O?fI?KGfC6lJu>lb; zuf<(FIj|KYru$JV81C#ir-8&h_fFRyRM-AB>Abu|f(2&F@|_)g%d4u3wAqnP$YUbA z-Ym2G*WJk=s5#ZmGM#Kcn&yyejo1Q2CxUvcme2dP1lMptp9V!@k%4t zK{2qbb4n_f0!>6l15*DL@Nfg(AA(_ttMB88ON1FyP#D)SF!;*Cl2K!vZ~v-K7I`i2 zTGJ>pKMslU>!Jy+KMxI7&yUMx3CeX@&9v#s$$ix3``~BX7BQJm`dTq1@E*>QYKscF z!T5(8l-N-J#4fS{bs2pT%7;<%W1>w@O~v6=OdD>XDTVz@k@v1YM%3T`@qUuObWxuqu4eIoTa~{;?d0SgV#DxJeKGonhcn zh#w5)L$cjX1Q-Fg+F-&7aO-a;=`L)HkglVjdP_YC%?dR4?>shB7_CtnoMFU zY7j&K!-w>4PNK9fiu=KG@M4mZ!DqxcL{af4{+`4KkbLWUA!7;RRUlz~kkb4lgov>} zUWX5b9)$uJ^k4+Zc7eQbQKy^&s!~XUG7SM5KRVWw8|4K&5Q?KZv^LMj&=@{J1UEqn zCevj>|KF9w4f|)dYd!_EU~t##?|qmTL#+Y83Aha};WrA1p0t9k! zRz}GDJ2aG_Vf&}nI7^IPFb4FH0whu~oLbaFCef-)gm&&?K2btJ^C`j$2057s=QvGt zT+Bda6`1r&xM_Eli)pXiAl8c_!j)I2UMygi=4tZ$UU!I$_@Ge03^-pD?1|yOBs79F zq>cA4V;!BBKh@aM55c28U7o3g{YxcU;NL zAQbp$V=d~q54LG{JPooG6hfj~(eGVuT7p__xihll(~ZUb@}Yde%@4IxM%&I)ou$K3 zjYO|jnFm4)*vBWhde$DICJ;SMCP88of`ZKsQ(g`j0Af^YNUJFvfz^a6orhn2wGh!f{~U`;&zL zTL^dY#DYkRH^y;#Vla8pZ1mOto_Fmk(~S4t%(DByReFr*$8ECP4_=)#@R9zL)KsBD z^iqHht#|*Lpjv|lsOg80fl=NAOe8%6m^$H4`io)7ExS9#Rw#uM8W&+cWLdW7Wh`=O z_(@n~pSoNIghltF<x;Wg-yU# zieFX*!S4aO8;LKFei2aszZ_zuQ2AxNq7jIy%?sh&b}x0=DO4*LwV=t1=&ojF?kJq> z2_!^Yv`B54ZcnN)&o+8bx$(Mw6jqwET0)QFR#~5G3C9iNbUn#MGja25W(o zZ@#s2WfW$7K=X%T7{LRDWIkl?(T6$)#vNG1Rs(h*CJjOp;Erq{1H;IEgkqft$^T&0 zKLkL@9ptyu(^Hd^Wq$xJ`0J}+l$qj#dT7aHbSwl`il3f zQ(g#_mn_l~Vn-qhS`lIz2*9kwqWIvfpw`3br9`S8(6j@y5#Dw9dx^)Os}^88GOQ1E zc63u%F?Yi`Zm=0(0KtX;q3Ryw7>JN@y`|;l1!wVOSpNEJYq;fxMLM6s zrrt#mu)m|e=O^#MfRoN1Sd!A!l0y;54e%bilNTgr|K$P*v6J>1aq*_!XOa|BaU3vs zbO5h1D#|x1kp;hih`1pmLnkmJp3Iiz*IUt(s>%LxiYP%tkB{;koqa^;ghE=LN8qlm zcKHE)DVIeCM+90R`X@~vfT7Cl4g}(bHD!MP?X5NyrDELBwmDAlQN$ZpgxY z91#EhjuJ?&eT07@9R^8-!bj0W=Jp^l#zk3ZPZaS702KNXB8=DuKrY+{ab7=5Gz2DK z%!MN8p%={{H*qrylcQdlXIK3|rDFqB;*=>5K*3dl|GC(55!@I}aBxerab}d@y}au^ z5V`dsgw#aKIcB<98Y9#K?f%UM8CZwNp_?>w+(=^!gdh>bC z?czvm7Weq+v~}-ZV`Vk9aFD!v-+JJtRRDc=QYU04+BaSwhuUc1IFSL@okRFnMVEA& zOurQp^8On%6Pk_Rp-Z}>Q-`7{CwE!m6aFUw|Lw6@xqiJ+(U1NVreVS}zG?}n_rdfo zc)0|)Y008bfJ*!74snOgpFe*+J!-HGp&`S6GIqGK?EA5=Q3p23%W@dkmsZ)oa z&WsYCWCrjC|8cBWIEW0x)-kIEwH3h$`GG(v0ftB_>luP7tKmkF_1Dwy?7k2Ke7*N= zEeQJlmY_xy7R$O~x2qME)>y8G21>Cptl-_g!R38cQPxg^V#N`uTnld9YaRr zIzFs{g-*-uWU~Z$Mia!`(=^OD*8)d0qEr%tF!^(o6cw$_xObkpX6A_)q5KDeJQcE_ z-*N5~QA2nKiJemuond>13y)gtMu_W2$9}#_NB?1SuOqA2o|HxbL{!H8ZP_Uc_W?yH zut$(q_vSY^0{JV!5sX&~SX{8ZaKsA~N&S2k1qV}ZMck`*#o`~&dk?KbOZG%w^b@}? z*@@7#sN!lsQ;$odAM%cBdUb7W1WE@qcSwWq%+|Q%7Xv-oiUT|7h{!vvLuJ};{2h&=)`0*@gA9AqA zVpF?vSb`ECIr2O}0z%hlYhA_0#(Vng*+6&1k-ekRNPtFv#5Bvs1kK1>Up$KZmqtf0 zQSfF$ncA#^rtZucjy;S!peYXanv#^~>@T9AZ7eWE#GK71W9L45&Q_$zq9*hR#ck7P zo-+f+nU2#U{snz_E)Fg~5sn>CPjXC3adaxR5LbbR9d#;3?}Jk4`cfXW72hCw0k42^ zIm{q0&eTvHoPE07J1;5+GX1m*ZCU5y2cLe9vHMa1>$SZt@$j9V%x9gxawI~_as3dq zdwm->p!GTrX%p?hv=-p{UCJQ`SoR~hWgzf!Va-^5ao0-Jz}0oO2D z>pANU4K^nsVfBVc7<7ok%usca0f>X3Hk950e^~atY^8dhbZ5}+PNLY*oj>rnv}mF; z5Y}8N3ox)riPs|1!H?W!Ytu6@$kAc;jOM`rc^pJay2Wl!btiD`CoxUSbP6im@&^tq zx>PM+1o;sLiU>yTWq|ibLASJ!?@DXOAjH8UloQatfg;_?L0F^;Vlja{_&Z=>_JE1e zPIpI+rJHNTNwP>>y+p@LM~f&Fc|@u8eME#s2)xHsS3D7j7WdK%SBN6t6Mcq%5bXlK z1C`%qlXXD{y@}e_h7EF#cj4k~j1wWK1qIm`Cqz!5dogp+>S-@K#KhGY1?N!!KCeg9 zQwJSc*c3iF`m2~T&h=@UG`-~{Qj8>BF7#d?Pa#5}fes)HO@7`x*GD%%RkIYfg6KvN zMozn5ex$5>K8+4x9T-YR!im<6xOsEqCrqXa&`QxZ!GfE1)T{3uw8;yF>-ccNb2>_Q z8wLx&P9AL@YJLT1st#jx2&)H`B_h#;q~b%mAwn%AqLq+P2ec?~ni;(ju8A zDdfFdUD2{QW=d#~YQZLBh>Mz@GG~iTO!-H8t0k7IY%jV3FSZQDVj=_!VCfGV87QPr ztFNjxJxDiRkoerP-H$*I;R9P0`#T!ric-0Eobs=CKd-}JBYw?0ZE)}0RB-B5zee*g zt7kKgbsjX!+<=_6FgcK-1yR=Vrvrgk&#Jkz^H6FowdY7dkKF0g3E$y+lyM48F*Su& zM$h(p0suB-+ys5T@oD+_dK?hhFmwHyQK6teSjF=u`A~}vL%`Lmp*wc$P@sVc$WQY` z7nCMWpqcSg+XS-|!>}^_&SMPDU*i05p%1`5$=C)$j)_ww$R_7Nx75U^>Ox|26CD~s z_7ZbgdEqu-Il`{0LhOMU!opiOizvb{tMRcT<}7Y&18}_w)crP#nXSUYVJOg6yPlbo zUCbk}z2Wi4(Uz0Jl8oh=Yv>hG*k-!M1v@Gc*q)|NpwavEAh@2l@UDDH5pyfXhr5ik zqGep0dW)p2-(RY>Ynv;uyjI0S%y`AJmFm)?S1gE?t2?vzuoteq&g_<9EtcqG1~W+< zI_lfZbr}BI>rpuQb?2SK?_eDG+sKJ&EvA>6&kKR|*oK9C)zqrPkfE2R38j^EHme6WFr{nI!WmGp;M^*8Fz4>i)l$D151xX7#NQVbkY%os)CZ7c?XXz#T&(RnE z!w6$Nq5?h_TbKC6C;bYAv>WcHgP>{+YEG_E#qkVNpVVaUAbaN)S4?4DOt@m5o^$Tf zQy*`V0WN3(DszNbg1z%soZ96AVah@@ogcpl5b&g?vU~REJ2E2w*SC5~hGiHT2D>}l z0{*O~t)!5qU7dWNr0HtG8HkyVM3;qu(Lw=~&sN=RU>B6?4h4_5efFlUvs|vpk#%cP zVJI&Iu7oj&sfN^M0@R@FVZ?1m*o+<^4rVsv^eraj-D+o6DBDyLlGKjW zdPJzRV0BSMpvKznNVClRfMF`D5EiYje)jWQVChp7OSwEIO_2R;fBe{_)A=)J>wx8) z2f#BY?Ca4(*4F^-_gR05n56pRR+BMd8tsU~WpftDTa+LV3AkN-vFEi){PRV%~L zHx^JUi`p1T$m0jG3HGB3da1hc7_>~bw~;zZ>vY8(Tt9$_<&;ZcV78t&TZx1S6D0y_ z#g#%&4HB#z5=Y3A1e#_LPh!#1ED8X0!fqWD0v^o?;Ua6#Q8kO!%md$#U`;wVqIeXU zWN^y3grA?kvReY)z_b`N^X~k9!m9yMePFCLS%K9M6wO6Mw2Cqbc7M(Iv?b~!zrU75 za7(oPV$T~6pKN8`q(K7^o8dNPo7?S!XeMz00L*sR=Zg(IMlPJ>X1IfnYqGH@&w(xx zRQLo8_-%}p0)DES=r=`|mzP-AbP|viKpm2}DJfk>Yul1{c?Daw{f)->uurdZhPY>E%9add%F{EbFbl~7Yq8K*`Xq#fdbdTU} zXeiB-c3ZIRnK-rZ+f~}h1z@rbBwFP36;cpf*(0BiEiTKtDF^{7qPb**kF13al~adOC}}iLq-m{?;;NB zDiw_ie`xEhtl2zi+JeOavxua#tS|WY4-s7mIRAMR;JRGgk@@$V2cjR(0mmjGPH@R0 z9cIt-P)Dic;-cv+m?8i*G$b?Jeoor7U+i)xkS;_se2{tM4|>Z?YwR0bT>iZG!U%dl zjtkL>r!Les%4Fyi#QV-cG44k?*}puspclLy%V#v1*qXecrwfP!y@f zRzoSI0w?xVJ^Ex1xH>ya0$*Q${lnliBqxk>R0r)^7t39$Ho4MP=*+p!`$@k*(5MIY zwYBaV(j01MYun$TPBejl5sm;9zsj@3`so~mRDG7n6Tu1C$#{3fb-LN+VKkm4?|(db zaR!#m)B|-!t`ttmg1whM$RHnCBRe~JGQ$eN5IDXEkwhjboV*Ed*6ErvvgG~GCuOSv zs^bjD?SQfil5-Bc$;tu8uPyW5+kSZ?tD6laIFLsoX6#lckJ3FTAw|UqJej6j=4j&+ z6BjfbIDt8}PIuH#eHHx5Vz`t~=>-Cp#qVt=|4)&Ion9qKCBy6pozUXTf_TBp?ph&8 zCDEyPud^bP`(-)GIOzY=5Mo|0!9oZ}#ZY*~Xzg|riKS=zzm14sS{Z!6s;M z;i#Pi70-yXI%=$q`S=NL>vS7O_5OHC-%XsqlF zhW0F1a&o=U?^3+ZDzC)EP~N!W=LI8SAUdQe=PK`x4P7Vh_ z#361{0qB0XakLhqo`7192sLxDCvAvh0W)(zY2_(C-e+nd@xDB>AuR5Qd_c&jJe^rf( zZ2Tws>z%dl!6qT%zay0!gZ~d=_YM$GFm~`7AUnG|>{l8&buZEt3J)J*zoBE%#lM(C zT;ZA^QTYS@z3Bb7+#2Z4TqiSvQJI2h*{S=n%oLQkMgYQNTn7V^sB#>d>$rtFkAbw@ z7iPOqaGn|2lGDGHjyObXkBxSAoN!-9!ES;qf>rqeclQ!%Il|MQW+3WaD0N*sCCq1! z$L!Qu?9r!pl~q(uH!kk4n(ZDfbRKJu5d>PrEc0EXsJ2m0GUX>ygiW6ewYy81 zc0zCn%rO`^GRW=VuKtF8;+x(-jIw%xis4cO7NmobXhVXD+xf18*H#b>?sVB`NxO%s zGI08@qiR06M3;K_Uq=mC?tWcm8#jvGE}YHlz@;McT)?V&ArFQb6TVl zsowfF=q2*|rjU+9Cnu+kf=DXDzbV_iu#ts{zynbxz6p(JaWQ;cT7D&N(aK4M?@3SygVcjZLU zF2@lXqM!l?p3@M|1fp8>h9rVk_PAZ-tBC@(Qp$l8ANmv1C=>?4;K zUP`)RI@f7Kmz+ZHXTTHyh~{3lXmhd{;K7Z+zr=ga%{oo>Mxf=^4}AT=IjcVuSfJC& zBrqgZhCE0QqsIe>jG4gHfPCJ)Gu&uf<>7xDgQ}&j`~?zh*-!YS(^?{hjZnG~jSUaq z{9@(v-o@8Duk7eIMSe??97MyX27(UW|2oeCZ!67p9?!vamTYLyN4AHnZeGdd{{2Ws zp>1!K_+Pw~ZCwR`4oO-KAU-s^mH8D5L=T7LKcS?QA@G2u9JAG7b3^I`=^Nf z1^iK!?~(c27H1IrNp>-)Xxn5rVmXmZo~D)(PE(^ZTH1tX2Ny3~_#S2Z@A@na z7mT11k|;$3ZBaBZ94$KXS0iCsIe;#?c@)%5e5z-mH&hwti8B`F{)Se74=5Wz$I|KH z8)E01{LN)hfnXazx4~7+>+$c!H=Og>|3NqX^x!|mp<^moGcvBo4LgR2I2Ql>rb7OFTf&By$TVa9 zt9=jgm@CmuSf<~52WdVkgLp^=CK7_cLWGRb>U;@7HVLk`#5le9APG}UN{eVo+$bZ% zNq7xVQvhL)$MtsWTBP?&%!qOq@S6j0J7^>(4YQ=tDB>9_+>L8+1twjU0I(kgiE%!K zfWbtt6U=u)R#S_W70xL_O2RR&r*{)IR72@&T^T1A6CDh2HDQk2=&ff>3qTtPn8NJ` z=8%zoueQWqiH+q(y_rZ1rs`!cL)LMn)#4zE80a-8-p`%}nvC8~JHb~Mmqh$Ybzzx7I$o#&T?HAp?b^1Zded!5Oi zX6S?Jxle_XwWvgu*^r)v3=be`OrMoNStmVgbSH?k$6IiN=vYT@(!U^Cw1qw$b$Ih} z8g|_Q{a9J|^>lZb?+$wFIzW~^YYC*TyBBDE#%!D)m+hC}6tt|U=cC0%;(EF14cLnT zdm8*FsAft~+M4Je*DG|&sGoKOTAe#Fjt#M9ASERw0XxLSp&0COQX(;)`w^jgv2?}m zh5=dHlf9idn&m%;(H}>WWz$kSE0d2L&d*VY+KXDHj8O_$ZxBs0>?}p2o0M^4$%&DE zSyF)w1;{iw4KjpF_AoLb&Nop2^k|=ui&{;en;Wj|_zu-w7l#gTqcUd**=vwJ@PJGIQADU1B<)Ig($0;00cp{4Q8#ER#-~$%lo2z z0DyScsu`9FB_b09`% zFLoxaF^%87R-RWhQT-rG9Cpjla8&)(cl{=LK`7b2UHgn3l zN%VN2ev<&zdjsU30eRBjN4)?kpH%acRaZ+q3WZY*Ox6G)_eIVV+Mo-H@899z?@(hw zWKc0?7qIt?3zI;mUDK!NIsCTS?8|vU{aUAw2`d{DK}eqAWQ2NTl*+9pu-ks5g5nvvJ{SiV!z-8^AYk+4#Y@yr<7LBX zgH3S4NstkK;`P!1pxWyR`{T#&U>?rt<5+)3yC0Af39p^6B(QaB9RTo}{>^cS;2nT@ z`49Kvc&5a~$pP&%sfIh_JleJ0An(Le{wM<`4+YSyZr%igD9^?S?*qE;hQmk@wNq&UtgD2n_F9JpsL*n z`+Xv2wz5S@3Nlm0fUmCXJ;TGIp|2l> zffy;Ecgeu7*h)n&bxwukFQn0v5)%)BCESJrnKW0eSEmky7xOVdvCxQ$qFoYdwEFwE z)_Nfk>O(-=KRgVjh!_ZHvDAm`vHOdQs|gLZV$jC~v;?|N9orJU!lqcd$q$SGG60#hm99aBCTr1?rKzGq$TY`*-LW_59UdGU%(we| z9d9@l8T{RdgPXe+=~mJVu=SLjcQiVQJy10`axvcpjLXZzu_j}Jg5cI`1k!)TAG-Zg+VUJXyEgrd@V z49DhTr}H6r&U}MyI^ZS$5@;so zab@3bz9<#_1N&FYz~Jt4qvOufT!24RB0bkWNJ~>i{i+FX^O{C5R4K&!?ZJyE>M1w@ zhEHwF89fQ%F)}75Cv~jduJ+NxhX)CC2H9eARQaSDkM=&XlVGZZIe7Cq= zd)Cs%CPPnOf6cR$w~dh6Ma6f-P9ePuYe_O0Re)7TQUA{G1GxHG)+o0F^tU-{hpE z+s(4be59yYPNBu<4M6!WJORya=S)psWX9B-sRu%kjkp^#cy-8v0&`*Gdhu|_zpF3p z4V}tk#>P}!PBQKqu$(54?G_iu0z+JK_$9PMC7|6jiFbY~3kC_h00MkH;3~}p@+e>W zAwgqL&u5r$V`|jZXK#*JuX@O?S%eWI=(apIF$I1H#zEL~qj~$>=3l-9;ma3Z+;z!f zz-*E;Gd1C+8qm2j{$lxd{+&DR&g~I?!Sl}}qs&}<@i-+#@av%=q&@;HORl8FMn_vN z^+RH%h0sI&qn{Oi^h6wEsm6s1RFoMLA%RKzDeDHBV9>Q|SJH;#Z0$u?~=Yo(KE|Y<4z~;IQy;y-3=iQBNnatJ;{>hzv5O6&tLk zk96A5(D~}CRYfKl;!ua@O=N8ReUAMDVRSBB$TblD>nAI8Fr@n(feSvlBJXt>T?=ea z4IXcjCTBkNRB35x`13<%BPSun((j1A3E-J_Eg}J61FN)5m&^UW&UAh}G^ss%HX5Ct zf}h2lS%Dr$Y$X(I!_9etDGF@crj1S;X|7-kaT*)<3cP)cw#PH$j*brV^XHGkTH=ul z#RX#oO%g4?W5|DAFM6p~j~CtiefoL2e|kJ?qtQzD^TH^bTUv&74F~6^RrjK!^u}LI zOLN}Opo>Q``pqV34!k|zI~;oacuo4D^hLvaG2d4_SWp2oX8C~a60rozI%d8cy}62AK6z9oMAYGAVK?QFlbPeYB@L~D4Xg& z-}rsjLjLK(-j5%3i>H0Gr@_U&)nR4qb>G>Am0=!!lzd4y`uh0^Z&`9CMgp^I>r%rG zJeaGxi~{AO^mGkm z>M;47$FG!C^!>WKIvN`HaI7~;W%l}2@%;KA3gy!2+RtNSUhB|x`G0TmORF!K znN_Ygmi^w}aA%9?r+j6x%0BzZMg?9UG(*|mijGeE`qct^ebeL@Ttp8n9fo!_&}b>} z%qp9L?`X;3=zbiVGHs*M2F0H-qjI(F>mE%gU?IDj^0?(Bd`0e`tEas6+;RXMhtGxm z*(oV1&{Gs0-Yq89$mr`N9V3~D^r|K-9W=CUva#ye_5Fi`VhgyQs7^p#dc9ZJ0{|3d z$7F=jwQ~7TfD_B_=g*^tcM7+zd@ZmsZj1iI#KaG67d16Qn;sjkvvVr@Fk0Dd&G$ud z9_9JX_v0>~8SSsAF*7jdaEQ zt`*8gJsx+_YLj;S$!2r?A{U2-(+ia-6vbIM1!&7Z%!NJ*dnSEz=pU(9?+-h zxO(_b#{z_(t0~W)ydIu7k6A@U-#u|vVnbIAOTr@~^Zjd=#2omu zR89wL3VWP$Qli#OU;V6sJ3|}E*s^e-EY+YHMV5Al)SS`3RXmTvRx8376dYVVFpi+( zwFQ=9Y?&Qow1xG$+O00O%UwTVClwvo#LUBW?DvXM#xU4{byT3=Oh@OCzBqu;q#2M@ zG+`%n75Q4u=!-W?fhK;dd-2HOZ&PmJ_g=mh-&x68YfEiTDVMgie9{{4yY%dGjyDG3 zH*Re3E6p&QnIF#fXWd2=re-|G`iGtN^T8Rhstf#ZE51T+?zKI@7zlZVs$SbWmZHNe z_swIe`aE{d&CLL+)o1i8XYSPBkkwza!$4VRJ=39<&*oX(<)4;0Z>n;!!p4*mrDarLFVbP%5%&$->utt)I%D z44GPRFIo6;V!C&1N+>tu@D>-t*xEH0%|4v-820gf&R($N$b;v;^?eW87}Br(*;y2) ztAF{%VafCS+-?u@P3-^V^G5x9i1hQD>>OvV9+TVB Date: Mon, 24 Feb 2025 21:37:06 +0800 Subject: [PATCH 07/21] feat: update LIVMapper.cpp --- src/LIVMapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/LIVMapper.cpp b/src/LIVMapper.cpp index eb3618dd..f3da37e5 100755 --- a/src/LIVMapper.cpp +++ b/src/LIVMapper.cpp @@ -799,7 +799,7 @@ void LIVMapper::livox_pcl_cbk(const livox_ros_driver2::msg::CustomMsg::ConstShar p_pre->process(msg, ptr); if (!ptr || ptr->empty()) { - ROS_ERROR("Received an empty point cloud"); + RCLCPP_ERROR(this->node->get_logger(), "Received an empty point cloud"); mtx_buffer.unlock(); return; } From d651afb292810a3d26869e74158f8207f60bfd4c Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Mon, 24 Feb 2025 21:38:02 +0800 Subject: [PATCH 08/21] feat: update fast_livo2.rviz --- rviz_cfg/fast_livo2.rviz | 281 +++++++++++++++++++++++++++------------ 1 file changed, 196 insertions(+), 85 deletions(-) diff --git a/rviz_cfg/fast_livo2.rviz b/rviz_cfg/fast_livo2.rviz index 9b69e325..f89870f5 100755 --- a/rviz_cfg/fast_livo2.rviz +++ b/rviz_cfg/fast_livo2.rviz @@ -4,6 +4,7 @@ Panels: Name: Displays Property Tree Widget: Expanded: + - /Global Options1 - /Status1 - /Axes1 - /mapping1 @@ -16,6 +17,7 @@ Panels: - /Odometry1/Odometry1/Shape1 - /Path1 - /currPoints1/Autocompute Value Bounds1 + - /Marker1 - /MarkerArray1/Namespaces1 - /currPoints2/Autocompute Value Bounds1 - /Odometry2/Shape1 @@ -23,14 +25,13 @@ Panels: - /MarkerArray4 - /MarkerArray5 - /Image1 - Splitter Ratio: 0.34272301197052 - Tree Height: 538 + Splitter Ratio: 0.5394402146339417 + Tree Height: 360 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties Expanded: - /2D Pose Estimate1 - - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 @@ -40,13 +41,10 @@ Panels: Name: Views Splitter Ratio: 0.5 - Class: rviz_common/Time + Experimental: false Name: Time SyncMode: 0 SyncSource: surround -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -68,14 +66,12 @@ Visualization Manager: Plane Cell Count: 160 Reference Frame: Value: false - - Alpha: 1 - Class: rviz_default_plugins/Axes + - Class: rviz_default_plugins/Axes Enabled: true Length: 0.699999988079071 Name: Axes Radius: 0.10000000149011612 - Reference Frame: - Show Trail: false + Reference Frame: camera_init Value: true - Class: rviz_common/Group Displays: @@ -94,16 +90,22 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: currPoints Position Transformer: XYZ - Queue Size: 100000 Selectable: true Size (Pixels): 4 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_registered - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_registered Use Fixed Frame: true Use rainbow: false Value: true @@ -127,13 +129,17 @@ Visualization Manager: Min Intensity: 5 Name: surround Position Transformer: XYZ - Queue Size: 1 Selectable: false Size (Pixels): 1 Size (m): 0.004999999888241291 Style: Points - Topic: /cloud_registered - Unreliable: true + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_registered Use Fixed Frame: true Use rainbow: true Value: true @@ -152,16 +158,22 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: PointCloud2 Position Transformer: XYZ - Queue Size: 10 Selectable: true Size (Pixels): 5 Size (m): 0.019999999552965164 Style: Squares - Topic: /cloud_effected - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_effected Use Fixed Frame: true Use rainbow: true Value: false @@ -190,7 +202,6 @@ Visualization Manager: Keep: 1 Name: Odometry Position Tolerance: 0.0010000000474974513 - Queue Size: 10 Shape: Alpha: 1 Axes Length: 0.5 @@ -201,8 +212,13 @@ Visualization Manager: Shaft Length: 0.800000011920929 Shaft Radius: 0.5 Value: Axes - Topic: /aft_mapped_to_init - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /aft_mapped_to_init Value: true Enabled: true Name: Odometry @@ -223,12 +239,16 @@ Visualization Manager: Z: 0 Pose Color: 25; 255; 255 Pose Style: None - Queue Size: 10 Radius: 0.029999999329447746 Shaft Diameter: 0.4000000059604645 Shaft Length: 0.4000000059604645 - Topic: /path - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /path Value: true - Alpha: 0.10000000149011612 Autocompute Intensity Bounds: true @@ -245,34 +265,49 @@ Visualization Manager: Enabled: false Invert Rainbow: true Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: currPoints Position Transformer: XYZ - Queue Size: 1 Selectable: true Size (Pixels): 2 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_voxel - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_voxel Use Fixed Frame: true Use rainbow: true Value: false - Class: rviz_default_plugins/Marker Enabled: true - Marker Topic: /planner_normal Name: Marker Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planner_normal Value: true - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /voxels Name: MarkerArray Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: visualization_marker_array Value: false - Alpha: 1 Autocompute Intensity Bounds: true @@ -289,26 +324,36 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: PointCloud2 Position Transformer: XYZ - Queue Size: 1 Selectable: true Size (Pixels): 15 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_ray_sub_map - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_ray_sub_map Use Fixed Frame: true Use rainbow: true Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /visualization_marker Name: MarkerArray Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: visualization_marker_array Value: false - Alpha: 1 Autocompute Intensity Bounds: true @@ -325,16 +370,22 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: PointCloud2 Position Transformer: XYZ - Queue Size: 10 Selectable: true Size (Pixels): 10 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_visual_map - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_visual_map Use Fixed Frame: true Use rainbow: true Value: false @@ -353,16 +404,22 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: surround Position Transformer: XYZ - Queue Size: 1 Selectable: false Size (Pixels): 12 Size (m): 0.05000000074505806 Style: Points - Topic: /cloud_visual_sub_map - Unreliable: true + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_visual_sub_map Use Fixed Frame: true Use rainbow: true Value: false @@ -381,16 +438,22 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: currPoints Position Transformer: XYZ - Queue Size: 100000 Selectable: true Size (Pixels): 5 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_sample_points - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_sample_points Use Fixed Frame: true Use rainbow: false Value: false @@ -409,16 +472,22 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 239; 41; 41 + Min Intensity: 0 Name: PointCloud2 Position Transformer: XYZ - Queue Size: 10 Selectable: true Size (Pixels): 4 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_visual_map - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_visual_map Use Fixed Frame: true Use rainbow: true Value: false @@ -437,16 +506,22 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 + Min Intensity: 0 Name: PointCloud2 Position Transformer: XYZ - Queue Size: 10 Selectable: true Size (Pixels): 20 Size (m): 0.009999999776482582 Style: Points - Topic: /cloud_ray_sub_map_fov - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_ray_sub_map_fov Use Fixed Frame: true Use rainbow: true Value: false @@ -471,7 +546,6 @@ Visualization Manager: Keep: 1 Name: Odometry Position Tolerance: 0 - Queue Size: 10 Shape: Alpha: 1 Axes Length: 0.699999988079071 @@ -482,49 +556,67 @@ Visualization Manager: Shaft Length: 1 Shaft Radius: 0.05000000074505806 Value: Axes - Topic: /aft_mapped_to_init - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /aft_mapped_to_init Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /waypoint_planner/visualize Name: MarkerArray Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: visualization_marker_array Value: false - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /fsm_node/visualization/exp_traj Name: MarkerArray Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: visualization_marker_array Value: true - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /fsm_node/visualization/exp_sfcs Name: MarkerArray Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: visualization_marker_array Value: false - Class: rviz_default_plugins/Image Enabled: true - Image Topic: /rgb_img Max Value: 1 Median window: 5 Min Value: 0 Name: Image Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /rgb_img Value: true Enabled: true Global Options: Background Color: 0; 0; 0 - Default Light: true Fixed Frame: camera_init Frame Rate: 30 Name: root @@ -535,27 +627,45 @@ Visualization Manager: - Class: rviz_default_plugins/Select - Class: rviz_default_plugins/FocusCamera - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 - Class: rviz_default_plugins/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose - Class: rviz_default_plugins/SetGoal - Topic: /move_base_simple/goal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /move_base_simple/goal - Class: rviz_default_plugins/PublishPoint Single click: true - Topic: /clicked_point + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF Value: true Views: Current: Class: rviz_default_plugins/ThirdPersonFollower - Distance: 25.669620513916016 + Distance: 50.66728210449219 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false - Field of View: 0.7853981852531433 Focal Point: X: 5.083343982696533 Y: -9.8687162399292 @@ -565,9 +675,10 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: -0.10520334541797638 + Pitch: 0.3547965884208679 Target Frame: drone - Yaw: 3.161787748336792 + Value: ThirdPersonFollower (rviz_default_plugins) + Yaw: 2.5417795181274414 Saved: - Class: rviz_default_plugins/Orbit Distance: 117.53474426269531 @@ -576,7 +687,6 @@ Visualization Manager: Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false - Field of View: 0.7853981852531433 Focal Point: X: -35.713138580322266 Y: 36.932613372802734 @@ -588,6 +698,7 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Pitch: 0.19539840519428253 Target Frame: + Value: Orbit (rviz_default_plugins) Yaw: 0.17540442943572998 - Class: rviz_default_plugins/Orbit Distance: 109.3125 @@ -596,7 +707,6 @@ Visualization Manager: Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false - Field of View: 0.7853981852531433 Focal Point: X: -22.092714309692383 Y: 63.322662353515625 @@ -608,6 +718,7 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Pitch: 0.035398442298173904 Target Frame: + Value: Orbit (rviz_default_plugins) Yaw: 5.793589115142822 - Class: rviz_default_plugins/Orbit Distance: 85.65605163574219 @@ -616,7 +727,6 @@ Visualization Manager: Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false - Field of View: 0.7853981852531433 Focal Point: X: 28.252656936645508 Y: -35.49672317504883 @@ -628,6 +738,7 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Pitch: 0.5653983950614929 Target Frame: + Value: Orbit (rviz_default_plugins) Yaw: 0.9104044437408447 - Class: rviz_default_plugins/Orbit Distance: 60.1053581237793 @@ -636,7 +747,6 @@ Visualization Manager: Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false - Field of View: 0.7853981852531433 Focal Point: X: 30.61589241027832 Y: 29.98663330078125 @@ -648,16 +758,17 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Pitch: 0.315398633480072 Target Frame: + Value: Orbit (rviz_default_plugins) Yaw: 5.788588047027588 Window Geometry: Displays: collapsed: false - Height: 1376 + Height: 1016 Hide Left Dock: false Hide Right Dock: false Image: collapsed: false - QMainWindow State: 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 + QMainWindow State: 000000ff00000000fd00000004000000000000018b00000357fc0200000019fb0000001200530065006c0065006300740069006f006e00000001530000005c0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001a5000000c900fffffffb0000000a0049006d00610067006501000001e8000001ac0000002800fffffffb0000000a0049006d00610067006501000001c7000001d60000000000000000fb0000000a0049006d00610067006500000001cc000001d10000000000000000fb0000000a0049006d00610067006500000002790000012a0000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006500000002470000015c0000000000000000fb0000000a0049006d00610067006501000002d8000000c30000000000000000fb0000000a0049006d00610067006501000002db000000c80000000000000000fb0000000c00430061006d00650072006101000002db000000c80000000000000000fb0000000a0049006d00610067006501000001ec000000eb0000000000000000fb0000000a0049006d00610067006501000002dd000000c80000000000000000fb0000000a0049006d00610067006501000001870000021e0000000000000000fb0000000a0049006d0061006700650000000243000000940000000000000000fb0000000a0049006d006100670065010000029a0000010b0000000000000000fb0000000a0049006d00610067006501000002d6000000c70000000000000000fb0000000a0049006d006100670065010000024c000001510000000000000000fb0000000a0049006d00610067006501000002d3000000c80000000000000000fb0000000a0049006d006100670065010000010c0000029100000000000000000000000100000152000004c8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004c8000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000749000000dbfc0100000005fb0000000a0049006d0061006700650100000000000007490000000000000000fb0000000a0049006d0061006700650100000000000007490000000000000000fb0000000a0049006d00610067006501000000000000062c0000000000000000fb0000000a0049006d00610067006501000000000000062c0000000000000000fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000078000000041fc0100000002fb0000000800540069006d0065010000000000000780000002fb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005ef0000035700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -666,6 +777,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Width: 2488 - X: 72 + Width: 1920 + X: 0 Y: 27 From e4c388b23305ce9c7cf6f4c6fa2415b218d74d32 Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Wed, 26 Feb 2025 20:54:46 +0800 Subject: [PATCH 09/21] bug: fix error of param getting of /laserMapping node --- config/avia.yaml | 6 +- include/LIVMapper.h | 4 +- src/LIVMapper.cpp | 228 ++++++++++++++++++++++---------------------- src/voxel_map.cpp | 52 +++++----- 4 files changed, 146 insertions(+), 144 deletions(-) diff --git a/config/avia.yaml b/config/avia.yaml index 9eb6b085..61d39346 100755 --- a/config/avia.yaml +++ b/config/avia.yaml @@ -10,7 +10,9 @@ extrin_calib: extrinsic_T: [0.04165, 0.02326, -0.0284] - extrinsic_R: [1, 0, 0, 0, 1, 0, 0, 0, 1] + extrinsic_R: [1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0] Rcl: [0.00610193,-0.999863,-0.0154172, -0.00615449,0.0153796,-0.999863, 0.999962,0.00619598,-0.0060598] @@ -61,7 +63,7 @@ local_map: map_sliding_en: false half_map_size: 100 - sliding_thresh: 8 + sliding_thresh: 8.0 uav: imu_rate_odom: false diff --git a/include/LIVMapper.h b/include/LIVMapper.h index fc127bd4..eb6170af 100644 --- a/include/LIVMapper.h +++ b/include/LIVMapper.h @@ -115,7 +115,7 @@ class LIVMapper int lidar_en = 1; bool is_first_frame = false; int grid_size, patch_size, grid_n_width, grid_n_height, patch_pyrimid_level; - double outlier_threshold; + int outlier_threshold; double plot_time; int frame_cnt; double img_time_offset = 0.0; @@ -129,7 +129,7 @@ class LIVMapper vector extrinR; vector cameraextrinT; vector cameraextrinR; - double IMG_POINT_COV; + int IMG_POINT_COV; PointCloudXYZI::Ptr visual_sub_map; PointCloudXYZI::Ptr feats_undistort; diff --git a/src/LIVMapper.cpp b/src/LIVMapper.cpp index f3da37e5..053a6dfe 100755 --- a/src/LIVMapper.cpp +++ b/src/LIVMapper.cpp @@ -53,128 +53,128 @@ LIVMapper::~LIVMapper() {} void LIVMapper::readParameters(rclcpp::Node::SharedPtr &node) { // declare parameters - this->node->declare_parameter("common/lid_topic", "/livox/lidar"); - this->node->declare_parameter("common/imu_topic", "/livox/imu"); - this->node->declare_parameter("common/ros_driver_bug_fix", false); - this->node->declare_parameter("common/img_en", 1); - this->node->declare_parameter("common/lidar_en", 1); - this->node->declare_parameter("common/img_topic", "/left_camera/image"); - - this->node->declare_parameter("vio/normal_en", true); - this->node->declare_parameter("vio/inverse_composition_en", false); - this->node->declare_parameter("vio/max_iterations", 5); - this->node->declare_parameter("vio/img_point_cov", 100); - this->node->declare_parameter("vio/raycast_en", false); - this->node->declare_parameter("vio/exposure_estimate_en", true); - this->node->declare_parameter("vio/inv_expo_cov", 0.1); - this->node->declare_parameter("vio/grid_size", 5); - this->node->declare_parameter("vio/grid_n_height", 17); - this->node->declare_parameter("vio/patch_pyrimid_level", 4); - this->node->declare_parameter("vio/patch_size", 8); - this->node->declare_parameter("vio/outlier_threshold", 100); - this->node->declare_parameter("time_offset/exposure_time_init", 0.0); - this->node->declare_parameter("time_offset/img_time_offset", 0.0); - this->node->declare_parameter("uav/imu_rate_odom", false); - this->node->declare_parameter("uav/gravity_align_en", false); - - this->node->declare_parameter("evo/seq_name", "01"); - this->node->declare_parameter("evo/pose_output_en", false); - this->node->declare_parameter("imu/gyr_cov", 1.0); - this->node->declare_parameter("imu/acc_cov", 1.0); - this->node->declare_parameter("imu/imu_int_frame", 30); - this->node->declare_parameter("imu/imu_en", true); - this->node->declare_parameter("imu/gravity_est_en", true); - this->node->declare_parameter("imu/ba_bg_est_en", true); - - this->node->declare_parameter("preprocess/blind", 0.01); - this->node->declare_parameter("preprocess/filter_size_surf", 0.5); - this->node->declare_parameter("preprocess/lidar_type", AVIA); - this->node->declare_parameter("preprocess/scan_line",6); - this->node->declare_parameter("preprocess/point_filter_num", 3); - this->node->declare_parameter("preprocess/feature_extract_enabled", false); - - this->node->declare_parameter("pcd_save/interval", -1); - this->node->declare_parameter("pcd_save/pcd_save_en", false); - this->node->declare_parameter("pcd_save/colmap_output_en", false); - this->node->declare_parameter("pcd_save/filter_size_pcd", 0.5); - this->node->declare_parameter>("extrin_calib/extrinsic_T", vector()); - this->node->declare_parameter>("extrin_calib/extrinsic_R", vector()); - this->node->declare_parameter>("extrin_calib/Pcl", vector()); - this->node->declare_parameter>("extrin_calib/Rcl", vector()); - this->node->declare_parameter("debug/plot_time", -10); - this->node->declare_parameter("debug/frame_cnt", 6); - - this->node->declare_parameter("publish/blind_rgb_points", 0.01); - this->node->declare_parameter("publish/pub_scan_num", 1); - this->node->declare_parameter("publish/pub_effect_point_en", false); - this->node->declare_parameter("publish/dense_map_en", false); + this->node->declare_parameter("common.lid_topic", "/livox/lidar"); + this->node->declare_parameter("common.imu_topic", "/livox/imu"); + this->node->declare_parameter("common.ros_driver_bug_fix", false); + this->node->declare_parameter("common.img_en", 1); + this->node->declare_parameter("common.lidar_en", 1); + this->node->declare_parameter("common.img_topic", "/left_camera/image"); + + this->node->declare_parameter("vio.normal_en", true); + this->node->declare_parameter("vio.inverse_composition_en", false); + this->node->declare_parameter("vio.max_iterations", 5); + this->node->declare_parameter("vio.img_point_cov", 100); + this->node->declare_parameter("vio.raycast_en", false); + this->node->declare_parameter("vio.exposure_estimate_en", true); + this->node->declare_parameter("vio.inv_expo_cov", 0.1); + this->node->declare_parameter("vio.grid_size", 5); + this->node->declare_parameter("vio.grid_n_height", 17); + this->node->declare_parameter("vio.patch_pyrimid_level", 4); + this->node->declare_parameter("vio.patch_size", 8); + this->node->declare_parameter("vio.outlier_threshold", 100); + this->node->declare_parameter("time_offset.exposure_time_init", 0.0); + this->node->declare_parameter("time_offset.img_time_offset", 0.0); + this->node->declare_parameter("uav.imu_rate_odom", false); + this->node->declare_parameter("uav.gravity_align_en", false); + + this->node->declare_parameter("evo.seq_name", "01"); + this->node->declare_parameter("evo.pose_output_en", false); + this->node->declare_parameter("imu.gyr_cov", 1.0); + this->node->declare_parameter("imu.acc_cov", 1.0); + this->node->declare_parameter("imu.imu_int_frame", 30); + this->node->declare_parameter("imu.imu_en", true); + this->node->declare_parameter("imu.gravity_est_en", true); + this->node->declare_parameter("imu.ba_bg_est_en", true); + + this->node->declare_parameter("preprocess.blind", 0.01); + this->node->declare_parameter("preprocess.filter_size_surf", 0.5); + this->node->declare_parameter("preprocess.lidar_type", AVIA); + this->node->declare_parameter("preprocess.scan_line",6); + this->node->declare_parameter("preprocess.point_filter_num", 3); + this->node->declare_parameter("preprocess.feature_extract_enabled", false); + + this->node->declare_parameter("pcd_save.interval", -1); + this->node->declare_parameter("pcd_save.pcd_save_en", false); + this->node->declare_parameter("pcd_save.colmap_output_en", false); + this->node->declare_parameter("pcd_save.filter_size_pcd", 0.5); + this->node->declare_parameter>("extrin_calib.extrinsic_T", vector{}); + this->node->declare_parameter>("extrin_calib.extrinsic_R", vector{}); + this->node->declare_parameter>("extrin_calib.Pcl", vector{}); + this->node->declare_parameter>("extrin_calib.Rcl", vector{}); + this->node->declare_parameter("debug.plot_time", -10); + this->node->declare_parameter("debug.frame_cnt", 6); + + this->node->declare_parameter("publish.blind_rgb_points", 0.01); + this->node->declare_parameter("publish.pub_scan_num", 1); + this->node->declare_parameter("publish.pub_effect_point_en", false); + this->node->declare_parameter("publish.dense_map_en", false); // get parameter - this->node->get_parameter("common/lid_topic", lid_topic); - this->node->get_parameter("common/imu_topic", imu_topic); - this->node->get_parameter("common/ros_driver_bug_fix", ros_driver_fix_en); - this->node->get_parameter("common/img_en", img_en); - this->node->get_parameter("common/lidar_en", lidar_en); - this->node->get_parameter("common/img_topic", img_topic); - - this->node->get_parameter("vio/normal_en", normal_en); - this->node->get_parameter("vio/inverse_composition_en", inverse_composition_en); - this->node->get_parameter("vio/max_iterations", max_iterations); - this->node->get_parameter("vio/img_point_cov", IMG_POINT_COV); - this->node->get_parameter("vio/raycast_en", raycast_en); - this->node->get_parameter("vio/exposure_estimate_en", exposure_estimate_en); - this->node->get_parameter("vio/inv_expo_cov", inv_expo_cov); - this->node->get_parameter("vio/grid_size", grid_size); - this->node->get_parameter("vio/grid_n_height", grid_n_height); - this->node->get_parameter("vio/patch_pyrimid_level", patch_pyrimid_level); - this->node->get_parameter("vio/patch_size", patch_size); - this->node->get_parameter("vio/outlier_threshold", outlier_threshold); - this->node->get_parameter("time_offset/exposure_time_init", exposure_time_init); - this->node->get_parameter("time_offset/img_time_offset", img_time_offset); - this->node->get_parameter("uav/imu_rate_odom", imu_prop_enable); - this->node->get_parameter("uav/gravity_align_en", gravity_align_en); - - this->node->get_parameter("evo/seq_name", seq_name); - this->node->get_parameter("evo/pose_output_en", pose_output_en); - this->node->get_parameter("imu/gyr_cov", gyr_cov); - this->node->get_parameter("imu/acc_cov", acc_cov); - this->node->get_parameter("imu/imu_int_frame", imu_int_frame); - this->node->get_parameter("imu/imu_en", imu_en); - this->node->get_parameter("imu/gravity_est_en", gravity_est_en); - this->node->get_parameter("imu/ba_bg_est_en", ba_bg_est_en); - - this->node->get_parameter("preprocess/blind", p_pre->blind); - this->node->get_parameter("preprocess/filter_size_surf", filter_size_surf_min); - this->node->get_parameter("preprocess/lidar_type", p_pre->lidar_type); - this->node->get_parameter("preprocess/scan_line", p_pre->N_SCANS); - this->node->get_parameter("preprocess/point_filter_num", p_pre->point_filter_num); - this->node->get_parameter("preprocess/feature_extract_enabled", p_pre->feature_enabled); - - this->node->get_parameter("pcd_save/interval", pcd_save_interval); - this->node->get_parameter("pcd_save/pcd_save_en", pcd_save_en); - this->node->get_parameter("pcd_save/colmap_output_en", colmap_output_en); - this->node->get_parameter("pcd_save/filter_size_pcd", filter_size_pcd); - this->node->get_parameter("extrin_calib/extrinsic_T", extrinT); - this->node->get_parameter("extrin_calib/extrinsic_R", extrinR); - this->node->get_parameter("extrin_calib/Pcl", cameraextrinT); - this->node->get_parameter("extrin_calib/Rcl", cameraextrinR); - this->node->get_parameter("debug/plot_time", plot_time); - this->node->get_parameter("debug/frame_cnt", frame_cnt); - - this->node->get_parameter("publish/blind_rgb_points", blind_rgb_points); - this->node->get_parameter("publish/pub_scan_num", pub_scan_num); - this->node->get_parameter("publish/pub_effect_point_en", pub_effect_point_en); - this->node->get_parameter("publish/dense_map_en", dense_map_en); + this->node->get_parameter("common.lid_topic", lid_topic); + this->node->get_parameter("common.imu_topic", imu_topic); + this->node->get_parameter("common.ros_driver_bug_fix", ros_driver_fix_en); + this->node->get_parameter("common.img_en", img_en); + this->node->get_parameter("common.lidar_en", lidar_en); + this->node->get_parameter("common.img_topic", img_topic); + + this->node->get_parameter("vio.normal_en", normal_en); + this->node->get_parameter("vio.inverse_composition_en", inverse_composition_en); + this->node->get_parameter("vio.max_iterations", max_iterations); + this->node->get_parameter("vio.img_point_cov", IMG_POINT_COV); + this->node->get_parameter("vio.raycast_en", raycast_en); + this->node->get_parameter("vio.exposure_estimate_en", exposure_estimate_en); + this->node->get_parameter("vio.inv_expo_cov", inv_expo_cov); + this->node->get_parameter("vio.grid_size", grid_size); + this->node->get_parameter("vio.grid_n_height", grid_n_height); + this->node->get_parameter("vio.patch_pyrimid_level", patch_pyrimid_level); + this->node->get_parameter("vio.patch_size", patch_size); + this->node->get_parameter("vio.outlier_threshold", outlier_threshold); + this->node->get_parameter("time_offset.exposure_time_init", exposure_time_init); + this->node->get_parameter("time_offset.img_time_offset", img_time_offset); + this->node->get_parameter("uav.imu_rate_odom", imu_prop_enable); + this->node->get_parameter("uav.gravity_align_en", gravity_align_en); + + this->node->get_parameter("evo.seq_name", seq_name); + this->node->get_parameter("evo.pose_output_en", pose_output_en); + this->node->get_parameter("imu.gyr_cov", gyr_cov); + this->node->get_parameter("imu.acc_cov", acc_cov); + this->node->get_parameter("imu.imu_int_frame", imu_int_frame); + this->node->get_parameter("imu.imu_en", imu_en); + this->node->get_parameter("imu.gravity_est_en", gravity_est_en); + this->node->get_parameter("imu.ba_bg_est_en", ba_bg_est_en); + + this->node->get_parameter("preprocess.blind", p_pre->blind); + this->node->get_parameter("preprocess.filter_size_surf", filter_size_surf_min); + this->node->get_parameter("preprocess.lidar_type", p_pre->lidar_type); + this->node->get_parameter("preprocess.scan_line", p_pre->N_SCANS); + this->node->get_parameter("preprocess.point_filter_num", p_pre->point_filter_num); + this->node->get_parameter("preprocess.feature_extract_enabled", p_pre->feature_enabled); + + this->node->get_parameter("pcd_save.interval", pcd_save_interval); + this->node->get_parameter("pcd_save.pcd_save_en", pcd_save_en); + this->node->get_parameter("pcd_save.colmap_output_en", colmap_output_en); + this->node->get_parameter("pcd_save.filter_size_pcd", filter_size_pcd); + this->node->get_parameter("extrin_calib.extrinsic_T", extrinT); + this->node->get_parameter("extrin_calib.extrinsic_R", extrinR); + this->node->get_parameter("extrin_calib.Pcl", cameraextrinT); + this->node->get_parameter("extrin_calib.Rcl", cameraextrinR); + this->node->get_parameter("debug.plot_time", plot_time); + this->node->get_parameter("debug.frame_cnt", frame_cnt); + + this->node->get_parameter("publish.blind_rgb_points", blind_rgb_points); + this->node->get_parameter("publish.pub_scan_num", pub_scan_num); + this->node->get_parameter("publish.pub_effect_point_en", pub_effect_point_en); + this->node->get_parameter("publish.dense_map_en", dense_map_en); } void LIVMapper::initializeComponents(rclcpp::Node::SharedPtr &node) { downSizeFilterSurf.setLeafSize(filter_size_surf_min, filter_size_surf_min, filter_size_surf_min); - extrinT.assign({0.04165, 0.02326, -0.0284}); - extrinR.assign({1, 0, 0, 0, 1, 0, 0, 0, 1}); - cameraextrinT.assign({0.0194384, 0.104689,-0.0251952}); - cameraextrinR.assign({0.00610193,-0.999863,-0.0154172,-0.00615449,0.0153796,-0.999863,0.999962,0.00619598,-0.0060598}); + // extrinT.assign({0.04165, 0.02326, -0.0284}); + // extrinR.assign({1, 0, 0, 0, 1, 0, 0, 0, 1}); + // cameraextrinT.assign({0.0194384, 0.104689,-0.0251952}); + // cameraextrinR.assign({0.00610193,-0.999863,-0.0154172,-0.00615449,0.0153796,-0.999863,0.999962,0.00619598,-0.0060598}); extT << VEC_FROM_ARRAY(extrinT); extR << MAT_FROM_ARRAY(extrinR); diff --git a/src/voxel_map.cpp b/src/voxel_map.cpp index 76c3c893..731222cd 100644 --- a/src/voxel_map.cpp +++ b/src/voxel_map.cpp @@ -36,36 +36,36 @@ void calcBodyCov(Eigen::Vector3d &pb, const float range_inc, const float degree_ void loadVoxelConfig(rclcpp::Node::SharedPtr &node, VoxelMapConfig &voxel_config) { // declare parameter - node->declare_parameter("publish/pub_plane_en", false); - node->declare_parameter("lio/max_layer", 1); - node->declare_parameter("lio/voxel_size", 0.5); - node->declare_parameter("lio/min_eigen_value", 0.01); - node->declare_parameter("lio/sigma_num", 3); - node->declare_parameter("lio/beam_err", 0.02); - node->declare_parameter("lio/dept_err", 0.05); + node->declare_parameter("publish.pub_plane_en", false); + node->declare_parameter("lio.max_layer", 1); + node->declare_parameter("lio.voxel_size", 0.5); + node->declare_parameter("lio.min_eigen_value", 0.01); + node->declare_parameter("lio.sigma_num", 3); + node->declare_parameter("lio.beam_err", 0.02); + node->declare_parameter("lio.dept_err", 0.05); // Declaration of parameter of type std::vector won't build, https://github.com/ros2/rclcpp/issues/1585 - node->declare_parameter>("lio/layer_init_num", std::vector{5,5,5,5,5}); - node->declare_parameter("lio/max_points_num", 50); - node->declare_parameter("lio/min_iterations", 5); - node->declare_parameter("local_map/map_sliding_en", false); - node->declare_parameter("local_map/half_map_size", 100); - node->declare_parameter("local_map/sliding_thresh", 8); + node->declare_parameter>("lio.layer_init_num", std::vector{5,5,5,5,5}); + node->declare_parameter("lio.max_points_num", 50); + node->declare_parameter("lio.min_iterations", 5); + node->declare_parameter("local_map.map_sliding_en", false); + node->declare_parameter("local_map.half_map_size", 100); + node->declare_parameter("local_map.sliding_thresh", 8.0); // get parameter - node->get_parameter("publish/pub_plane_en", voxel_config.is_pub_plane_map_); - node->get_parameter("lio/max_layer", voxel_config.max_layer_); - node->get_parameter("lio/voxel_size", voxel_config.max_voxel_size_); - node->get_parameter("lio/min_eigen_value", voxel_config.planner_threshold_); - node->get_parameter("lio/sigma_num", voxel_config.sigma_num_); - node->get_parameter("lio/beam_err", voxel_config.beam_err_); - node->get_parameter("lio/dept_err", voxel_config.dept_err_); - node->get_parameter("lio/layer_init_num", voxel_config.layer_init_num_); - node->get_parameter("lio/max_points_num", voxel_config.max_points_num_); - node->get_parameter("lio/min_iterations", voxel_config.max_iterations_); - node->get_parameter("local_map/map_sliding_en", voxel_config.map_sliding_en); - node->get_parameter("local_map/half_map_size", voxel_config.half_map_size); - node->get_parameter("local_map/sliding_thresh", voxel_config.sliding_thresh); + node->get_parameter("publish.pub_plane_en", voxel_config.is_pub_plane_map_); + node->get_parameter("lio.max_layer", voxel_config.max_layer_); + node->get_parameter("lio.voxel_size", voxel_config.max_voxel_size_); + node->get_parameter("lio.min_eigen_value", voxel_config.planner_threshold_); + node->get_parameter("lio.sigma_num", voxel_config.sigma_num_); + node->get_parameter("lio.beam_err", voxel_config.beam_err_); + node->get_parameter("lio.dept_err", voxel_config.dept_err_); + node->get_parameter("lio.layer_init_num", voxel_config.layer_init_num_); + node->get_parameter("lio.max_points_num", voxel_config.max_points_num_); + node->get_parameter("lio.min_iterations", voxel_config.max_iterations_); + node->get_parameter("local_map.map_sliding_en", voxel_config.map_sliding_en); + node->get_parameter("local_map.half_map_size", voxel_config.half_map_size); + node->get_parameter("local_map.sliding_thresh", voxel_config.sliding_thresh); } void VoxelOctoTree::init_plane(const std::vector &points, VoxelPlane *plane) From 81cb62828b6ae8607ce1eeb883e213f748c6c87e Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Wed, 26 Feb 2025 21:17:21 +0800 Subject: [PATCH 10/21] bug: fix error of param getting of in ROS2 --- launch/mapping_aviz.launch.py | 20 ++++++++++---------- src/LIVMapper.cpp | 2 +- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/launch/mapping_aviz.launch.py b/launch/mapping_aviz.launch.py index d9488b03..98716d20 100644 --- a/launch/mapping_aviz.launch.py +++ b/launch/mapping_aviz.launch.py @@ -61,16 +61,16 @@ def generate_launch_description(): # ), # use parameter_blackboard as global parameters server and load camera params - # Node( - # package='demo_nodes_cpp', - # executable='parameter_blackboard', - # name='parameter_blackboard', - # # namespace='laserMapping', - # parameters=[ - # camera_params_file - # ], - # output='screen' - # ), + Node( + package='demo_nodes_cpp', + executable='parameter_blackboard', + name='parameter_blackboard', + # namespace='laserMapping', + parameters=[ + camera_params_file, + ], + output='screen' + ), # republish compressed image to raw image # https://robotics.stackexchange.com/questions/110939/how-do-i-remap-compressed-video-to-raw-video-in-ros2 diff --git a/src/LIVMapper.cpp b/src/LIVMapper.cpp index 053a6dfe..0968df84 100755 --- a/src/LIVMapper.cpp +++ b/src/LIVMapper.cpp @@ -182,7 +182,7 @@ void LIVMapper::initializeComponents(rclcpp::Node::SharedPtr &node) voxelmap_manager->extT_ << VEC_FROM_ARRAY(extrinT); voxelmap_manager->extR_ << MAT_FROM_ARRAY(extrinR); - if (!vk::camera_loader::loadFromRosNs(this->node, "laserMapping", vio_manager->cam)) throw std::runtime_error("Camera model not correctly specified."); + if (!vk::camera_loader::loadFromRosNs(this->node, "parameter_blackboard", vio_manager->cam)) throw std::runtime_error("Camera model not correctly specified."); vio_manager->grid_size = grid_size; vio_manager->patch_size = patch_size; From b5be58727cc6dccd7607c9a442f9e6e29f68f8ac Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Fri, 28 Feb 2025 20:57:36 +0800 Subject: [PATCH 11/21] feat: add .log of valgrind in launch.py --- launch/mapping_aviz.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/mapping_aviz.launch.py b/launch/mapping_aviz.launch.py index 98716d20..a9b17a59 100644 --- a/launch/mapping_aviz.launch.py +++ b/launch/mapping_aviz.launch.py @@ -100,8 +100,8 @@ def generate_launch_description(): ], # https://docs.ros.org/en/humble/How-To-Guides/Getting-Backtraces-in-ROS-2.html prefix=[ - # ("gdb -ex run --args"), - # ("valgrind --tool=memcheck --leak-check=full --show-reachable=yes --undef-value-errors=yes --track-fds=yes") + # ("gdb -ex run --args"), + # ("valgrind --log-file=./valgrind_report.log --tool=memcheck --leak-check=full --show-leak-kinds=all -s --track-origins=yes --show-reachable=yes --undef-value-errors=yes --track-fds=yes") ], output="screen" ), From 8508f53c09816db594200c82131d7dd579bf11ac Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Sat, 1 Mar 2025 21:24:48 +0800 Subject: [PATCH 12/21] docs: update README.md --- README.md | 93 +++++++++++++++++++++++++++++++++++++++++++++++-------- 1 file changed, 80 insertions(+), 13 deletions(-) diff --git a/README.md b/README.md index eac5d4e6..82c945f0 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,9 @@ -# FAST-LIVO2 +# FAST-LIVO2 ROS2 HUMBLE ## FAST-LIVO2: Fast, Direct LiDAR-Inertial-Visual Odometry +Thanks to hku mars lab chunran zheng for the open source excellent work + ### 📢 News - 🔓 **2025-01-23**: Code released! @@ -41,7 +43,7 @@ Our associate dataset [**FAST-LIVO2-Dataset**](https://connecthkuhk-my.sharepoin ### 2.1 Ubuntu and ROS -Ubuntu 16.04~20.04. [ROS Installation](http://wiki.ros.org/ROS/Installation). +Ubuntu 22.04. [ROS Installation](http://wiki.ros.org/ROS/Installation). ### 2.2 PCL && Eigen && OpenCV @@ -64,41 +66,106 @@ make sudo make install ``` +if build fails due to `so2.cpp:32:26: error: lvalue required as left operand of assignment`, modify the code as follows: + +**so2.cpp** +```diff +namespace Sophus +{ + +SO2::SO2() +{ +- unit_complex_.real() = 1.; +- unit_complex_.imag() = 0.; ++ unit_complex_.real(1.); ++ unit_complex_.imag(0.); +} +``` + ### 2.4 Vikit Vikit contains camera models, some math and interpolation functions that we need. Vikit is a catkin project, therefore, download it into your catkin workspace source folder. +For well-known reasons, ROS2 does not have a direct global parameter server and a simple method to obtain the corresponding parameters. For details, please refer to https://discourse.ros.org/t/ros2-global-parameter-server-status/10114/11. I use a special way to get camera parameters in Vikit. While the method I've provided so far is quite simple and not perfect, it meets my needs. More contributions to improve `rpg_vikit` are hoped. + ```bash # Different from the one used in fast-livo1 -cd catkin_ws/src -git clone https://github.com/xuankuzcr/rpg_vikit.git +cd fast_ws/src +git clone https://github.com/Robotic-Developer-Road/rpg_vikit.git ``` -### 2.5 **livox_ros_driver** +Thanks to the following repositories for the code reference: + +- [uzh-rpg/rpg_vikit](https://github.com/uzh-rpg/rpg_vikit) +- [xuankuzcr/rpg_vikit](https://github.com/xuankuzcr/rpg_vikit) +- [uavfly/vikit](https://github.com/uavfly/vikit) -Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver). +### 2.5 **livox_ros_driver2** + +Follow [livox_ros_driver2 Installation](https://github.com/Livox-SDK/livox_ros_driver2). + +why not use `livox_ros_driver`? Because it is not compatible with ROS2 directly. actually i am not think there s any difference between [livox ros driver](https://github.com/Livox-SDK/livox_ros_driver.git) and [livox ros driver2](https://github.com/Livox-SDK/livox_ros_driver2.git) 's `CustomMsg`, the latter 's ros2 version is sufficient. ## 3. Build -Clone the repository and catkin_make: +Clone the repository and colcon build: ``` -cd ~/catkin_ws/src -git clone https://github.com/hku-mars/FAST-LIVO2 +cd ~/fast_ws/src +git clone https://github.com/Robotic-Developer-Road/FAST-LIVO2.git cd ../ -catkin_make -source ~/catkin_ws/devel/setup.bash +colcon build --symlink-install --continue-on-error +source ~/fast_ws/install/setup.bash ``` ## 4. Run our examples Download our collected rosbag files via OneDrive ([**FAST-LIVO2-Dataset**](https://connecthkuhk-my.sharepoint.com/:f:/g/personal/zhengcr_connect_hku_hk/ErdFNQtjMxZOorYKDTtK4ugBkogXfq1OfDm90GECouuIQA?e=KngY9Z)). +### convert rosbag + +convert ROS1 rosbag to ROS2 rosbag +```bash +rosbags-convert --src Retail_Street.bag --dst Retail_Street ``` -roslaunch fast_livo mapping_avia.launch -rosbag play YOUR_DOWNLOADED.bag +- [gitlab rosbags](https://gitlab.com/ternaris/rosbags) +- [pypi rosbags](https://pypi.org/project/rosbags/) + +### change the msg type on rosbag + +Such as dataset `Retail_Street.db3`, because we use `livox_ros2_driver2`'s `CustomMsg`, we need to change the msg type in the rosbag file. We use `rosbag2 modify` to change the msg type. + +**metadata.yaml** +```diff +rosbag2_bagfile_information: + compression_format: '' + compression_mode: '' + custom_data: {} + duration: + nanoseconds: 135470252209 + files: + - duration: + nanoseconds: 135470252209 + message_count: 30157 + path: Retail_Street.db3 + .............. + topic_metadata: + name: /livox/lidar + offered_qos_profiles: '' + serialization_format: cdr +- type: livox_ros_driver/msg/CustomMsg ++ type: livox_ros_driver2/msg/CustomMsg + type_description_hash: RIHS01_94041b4794f52c1d81def2989107fc898a62dacb7a39d5dbe80d4b55e538bf6d + ............... +..... ``` +Do not forget to source your ROS2 workspace before running the following command. + +```bash +ros2 launch fast_livo mapping_aviz.launch.py use_rviz:=True +ros2 bag play -p Retail_Street # space bar controls play/pause +``` ## 5. License From 19febb9048e2a3945ee1c14b78ed84cf8150464f Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Sat, 1 Mar 2025 21:50:29 +0800 Subject: [PATCH 13/21] upstream: add support for MARS-LVIG dataset --- config/MARS_LVIG.yaml | 204 +++++++++++++------------ config/camera_MARS_LVIG.yaml | 52 ++++--- launch/mapping_avia_marslvig.launch | 20 --- launch/mapping_avia_marslvig.launch.py | 111 ++++++++++++++ rviz_cfg/M300.rviz | 84 +++++----- 5 files changed, 283 insertions(+), 188 deletions(-) delete mode 100755 launch/mapping_avia_marslvig.launch create mode 100755 launch/mapping_avia_marslvig.launch.py diff --git a/config/MARS_LVIG.yaml b/config/MARS_LVIG.yaml index 34b84fc7..5c7c9e1e 100644 --- a/config/MARS_LVIG.yaml +++ b/config/MARS_LVIG.yaml @@ -1,111 +1,113 @@ -common: - img_topic: "/left_camera/image" - lid_topic: "/livox/lidar" - imu_topic: "/livox/imu" - img_en: 1 - lidar_en: 1 - ros_driver_bug_fix: false +/**: + ros__parameters: + common: + img_topic: "/left_camera/image" + lid_topic: "/livox/lidar" + imu_topic: "/livox/imu" + img_en: 1 + lidar_en: 1 + ros_driver_bug_fix: false -extrin_calib: - extrinsic_T: [0.04165, 0.02326, -0.0284] - extrinsic_R: [1, 0, 0, 0, 1, 0, 0, 0, 1] - # MARS_LVIG HKisland HKairport - Rcl: [0.00438814,-0.999807,-0.0191582, - -0.00978695,0.0191145,-0.999769, - 0.999942,0.00457463,-0.00970118] - Pcl: [0.016069, 0.0871753, -0.0718021] - # MARS_LVIG AMtown AMvalley - # Rcl: [ -0.0022464, -0.9997299, -0.0231319, - # -0.0084211, 0.0231501, -0.9996966, - # 0.9999620, -0.0020509, -0.0084708] - # Pcl: [-0.0025563, 0.0567484, -0.0512149] + extrin_calib: + extrinsic_T: [0.04165, 0.02326, -0.0284] + extrinsic_R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] + # MARS_LVIG HKisland HKairport + Rcl: [0.00438814,-0.999807,-0.0191582, + -0.00978695,0.0191145,-0.999769, + 0.999942,0.00457463,-0.00970118] + Pcl: [0.016069, 0.0871753, -0.0718021] + # MARS_LVIG AMtown AMvalley + # Rcl: [ -0.0022464, -0.9997299, -0.0231319, + # -0.0084211, 0.0231501, -0.9996966, + # 0.9999620, -0.0020509, -0.0084708] + # Pcl: [-0.0025563, 0.0567484, -0.0512149] -time_offset: - imu_time_offset: 0.0 - img_time_offset: -0.1 - exposure_time_init: 0.0 -# ╔═══════════════════════════════════════════════════════════════════════════════════════╗ -# ║ Configuration Settings ║ -# ╠═══════════════════════════════════════════════════════════════════════════════════════╣ -# ║ Series │ ID │ img_time_offset │ exposure_time_init │ -s (start hover) ║ -# ╠═══════════════════════════════════════════════════════════════════════════════════════╣ -# ║ HKairport │ HKairport01 │ 0.1 │ 0.0 │ 75 ║ -# ║ │ HKairport02 │ -0.1 │ 0.0 │ 60 ║ -# ║ │ HKairport03 │ -0.1 │ 0.0 │ 62 ║ -# ╠═══════════════════════════════════════════════════════════════════════════════════════╣ -# ║ HKisland │ HKisland01 │ 0.0 │ 0.0 │ 118 ║ -# ║ │ HKisland02 │ 0.1 │ 0.0 │ 80 ║ -# ║ │ HKisland03 │ -0.1 │ 0.0 │ 72 ║ -# ╠═══════════════════════════════════════════════════════════════════════════════════════╣ -# ║ AMtown │ AMtown01 │ -0.1 │ 0.0285 │ 75 ║ -# ║ │ AMtown02 │ -0.1 │ 0.0285 │ 50 ║ -# ║ │ AMtown03 │ -0.1 │ 0.0285 │ 106 ║ -# ╠═══════════════════════════════════════════════════════════════════════════════════════╣ -# ║ AMvalley │ AMvalley01 │ -0.1 │ 0.0132 │ 70 ║ -# ║ │ AMvalley02 │ -0.1 │ 0.0132 │ 65 ║ -# ║ │ AMvalley03 │ -0.1 │ 0.0132 │ 68 ║ -# ╚═══════════════════════════════════════════════════════════════════════════════════════╝ -preprocess: - point_filter_num: 1 - filter_size_surf: 0.1 - lidar_type: 1 # Livox Avia LiDAR - scan_line: 6 - blind: 0.8 + time_offset: + imu_time_offset: 0.0 + img_time_offset: -0.1 + exposure_time_init: 0.0 + # ╔═══════════════════════════════════════════════════════════════════════════════════════╗ + # ║ Configuration Settings ║ + # ╠═══════════════════════════════════════════════════════════════════════════════════════╣ + # ║ Series │ ID │ img_time_offset │ exposure_time_init │ -s (start hover) ║ + # ╠═══════════════════════════════════════════════════════════════════════════════════════╣ + # ║ HKairport │ HKairport01 │ 0.1 │ 0.0 │ 75 ║ + # ║ │ HKairport02 │ -0.1 │ 0.0 │ 60 ║ + # ║ │ HKairport03 │ -0.1 │ 0.0 │ 62 ║ + # ╠═══════════════════════════════════════════════════════════════════════════════════════╣ + # ║ HKisland │ HKisland01 │ 0.0 │ 0.0 │ 118 ║ + # ║ │ HKisland02 │ 0.1 │ 0.0 │ 80 ║ + # ║ │ HKisland03 │ -0.1 │ 0.0 │ 72 ║ + # ╠═══════════════════════════════════════════════════════════════════════════════════════╣ + # ║ AMtown │ AMtown01 │ -0.1 │ 0.0285 │ 75 ║ + # ║ │ AMtown02 │ -0.1 │ 0.0285 │ 50 ║ + # ║ │ AMtown03 │ -0.1 │ 0.0285 │ 106 ║ + # ╠═══════════════════════════════════════════════════════════════════════════════════════╣ + # ║ AMvalley │ AMvalley01 │ -0.1 │ 0.0132 │ 70 ║ + # ║ │ AMvalley02 │ -0.1 │ 0.0132 │ 65 ║ + # ║ │ AMvalley03 │ -0.1 │ 0.0132 │ 68 ║ + # ╚═══════════════════════════════════════════════════════════════════════════════════════╝ + preprocess: + point_filter_num: 1 + filter_size_surf: 0.1 + lidar_type: 1 # Livox Avia LiDAR + scan_line: 6 + blind: 0.8 -vio: - max_iterations: 5 - outlier_threshold: 1000 # 78 100 156 #100 200 500 700 infinite - img_point_cov: 1000 # 100 1000 - patch_size: 8 - patch_pyrimid_level: 4 - normal_en: true - raycast_en: false - inverse_composition_en: false - exposure_estimate_en: true - inv_expo_cov: 0.1 + vio: + max_iterations: 5 + outlier_threshold: 1000 # 78 100 156 #100 200 500 700 infinite + img_point_cov: 1000 # 100 1000 + patch_size: 8 + patch_pyrimid_level: 4 + normal_en: true + raycast_en: false + inverse_composition_en: false + exposure_estimate_en: true + inv_expo_cov: 0.1 -imu: - imu_en: true - imu_int_frame: 30 - acc_cov: 2.0 # 0.5 - gyr_cov: 0.1 # 0.3 - b_acc_cov: 0.0001 # 0.1 - b_gyr_cov: 0.0001 # 0.1 + imu: + imu_en: true + imu_int_frame: 30 + acc_cov: 2.0 # 0.5 + gyr_cov: 0.1 # 0.3 + b_acc_cov: 0.0001 # 0.1 + b_gyr_cov: 0.0001 # 0.1 -lio: - max_iterations: 5 - dept_err: 0.02 - beam_err: 0.05 - min_eigen_value: 0.005 - voxel_size: 2.0 # 1.0 - max_layer: 2 - max_points_num: 50 - layer_init_num: [5, 5, 5, 5, 5] + lio: + max_iterations: 5 + dept_err: 0.02 + beam_err: 0.05 + min_eigen_value: 0.005 + voxel_size: 2.0 # 1.0 + max_layer: 2 + max_points_num: 50 + layer_init_num: [5, 5, 5, 5, 5] -local_map: - map_sliding_en: false - half_map_size: 100 - sliding_thresh: 8 + local_map: + map_sliding_en: false + half_map_size: 100 + sliding_thresh: 8.0 -uav: - imu_rate_odom: false - gravity_align_en: false + uav: + imu_rate_odom: false + gravity_align_en: false -publish: - dense_map_en: true - pub_effect_point_en: false - pub_plane_en: false - pub_scan_num: 1 - blind_rgb_points: 0.0 + publish: + dense_map_en: true + pub_effect_point_en: false + pub_plane_en: false + pub_scan_num: 1 + blind_rgb_points: 0.0 -evo: - seq_name: "HKisland03" - pose_output_en: false + evo: + seq_name: "HKisland03" + pose_output_en: false -pcd_save: - pcd_save_en: false - colmap_output_en: false # need to set interval = -1 - filter_size_pcd: 0.15 - interval: -1 - # how many LiDAR frames saved in each pcd file; - # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. \ No newline at end of file + pcd_save: + pcd_save_en: false + colmap_output_en: false # need to set interval = -1 + filter_size_pcd: 0.15 + interval: -1 + # how many LiDAR frames saved in each pcd file; + # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. \ No newline at end of file diff --git a/config/camera_MARS_LVIG.yaml b/config/camera_MARS_LVIG.yaml index 698d6484..4b4e09fc 100644 --- a/config/camera_MARS_LVIG.yaml +++ b/config/camera_MARS_LVIG.yaml @@ -1,26 +1,28 @@ -cam_model: Pinhole -# HKisland HKairport -cam_width: 2448 -cam_height: 2048 -scale: 0.25 -cam_fx: 1444.431662789634 -cam_fy: 1444.343536688358 -cam_cx: 1177.801079401826 -cam_cy: 1043.601026568268 -cam_d0: -0.05729528706141188 -cam_d1: 0.1210407244166642 -cam_d2: 0.001274128378760289 -cam_d3: 0.0004389741530109464 +/**: + ros__parameters: + cam_model: Pinhole + # HKisland HKairport + cam_width: 2448 + cam_height: 2048 + scale: 0.25 + cam_fx: 1444.431662789634 + cam_fy: 1444.343536688358 + cam_cx: 1177.801079401826 + cam_cy: 1043.601026568268 + cam_d0: -0.05729528706141188 + cam_d1: 0.1210407244166642 + cam_d2: 0.001274128378760289 + cam_d3: 0.0004389741530109464 -# AMtown AMvalley -# cam_width: 2448 -# cam_height: 2048 -# scale: 0.25 -# cam_fx: 1453.88 -# cam_fy: 1452.85 -# cam_cx: 1182.53 -# cam_cy: 1045.82 -# cam_d0: -0.052 -# cam_d1: 0.1168 -# cam_d2: 0.0015 -# cam_d3: 0.00013 \ No newline at end of file + # AMtown AMvalley + # cam_width: 2448 + # cam_height: 2048 + # scale: 0.25 + # cam_fx: 1453.88 + # cam_fy: 1452.85 + # cam_cx: 1182.53 + # cam_cy: 1045.82 + # cam_d0: -0.052 + # cam_d1: 0.1168 + # cam_d2: 0.0015 + # cam_d3: 0.00013 \ No newline at end of file diff --git a/launch/mapping_avia_marslvig.launch b/launch/mapping_avia_marslvig.launch deleted file mode 100755 index 2fa90d3d..00000000 --- a/launch/mapping_avia_marslvig.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - -launch-prefix="gdb -ex run --args" -launch-prefix="valgrind --leak-check=full" - diff --git a/launch/mapping_avia_marslvig.launch.py b/launch/mapping_avia_marslvig.launch.py new file mode 100755 index 00000000..7e787500 --- /dev/null +++ b/launch/mapping_avia_marslvig.launch.py @@ -0,0 +1,111 @@ +#!/usr/bin/python3 +# -- coding: utf-8 --** + +import os +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from ament_index_python.packages import get_package_share_directory +from launch_ros.actions import Node + +def generate_launch_description(): + + # Find path + config_file_dir = os.path.join(get_package_share_directory("fast_livo"), "config") + rviz_config_file = os.path.join(get_package_share_directory("fast_livo"), "rviz_cfg", "M300.rviz") + + #Load parameters + avia_config_cmd = os.path.join(config_file_dir, "MARS_LVIG.yaml") + camera_config_cmd = os.path.join(config_file_dir, "camera_MARS_LVIG.yaml") + + # Param use_rviz + use_rviz_arg = DeclareLaunchArgument( + "use_rviz", + default_value="False", + description="Whether to launch Rviz2", + ) + + avia_config_arg = DeclareLaunchArgument( + 'avia_params_file', + default_value=avia_config_cmd, + description='Full path to the ROS2 parameters file to use for fast_livo2 nodes', + ) + + camera_config_arg = DeclareLaunchArgument( + 'camera_params_file', + default_value=camera_config_cmd, + description='Full path to the ROS2 parameters file to use for vikit_ros nodes', + ) + + # https://github.com/ros-navigation/navigation2/blob/1c68c212db01f9f75fcb8263a0fbb5dfa711bdea/nav2_bringup/launch/navigation_launch.py#L40 + use_respawn_arg = DeclareLaunchArgument( + 'use_respawn', + default_value='True', + description='Whether to respawn if a node crashes. Applied when composition is disabled.') + + avia_params_file = LaunchConfiguration('avia_params_file') + camera_params_file = LaunchConfiguration('camera_params_file') + use_respawn = LaunchConfiguration('use_respawn') + + return LaunchDescription([ + use_rviz_arg, + avia_config_arg, + camera_config_arg, + use_respawn_arg, + + # use parameter_blackboard as global parameters server and load camera params + Node( + package='demo_nodes_cpp', + executable='parameter_blackboard', + name='parameter_blackboard', + # namespace='laserMapping', + parameters=[ + camera_params_file, + ], + output='screen' + ), + + # republish compressed image to raw image + # https://robotics.stackexchange.com/questions/110939/how-do-i-remap-compressed-video-to-raw-video-in-ros2 + # ros2 run image_transport republish compressed raw --ros-args --remap in:=/left_camera/image --remap out:=/left_camera/image + Node( + package="image_transport", + executable="republish", + name="republish", + arguments=[ # Array of strings/parametric arguments that will end up in process's argv + 'compressed', + 'raw', + ], + remappings=[ + ("in", "/left_camera/image"), + ("out", "/left_camera/image") + ], + output="screen", + respawn=use_respawn, + ), + + Node( + package="fast_livo", + executable="fastlivo_mapping", + name="laserMapping", + parameters=[ + avia_params_file, + ], + # https://docs.ros.org/en/humble/How-To-Guides/Getting-Backtraces-in-ROS-2.html + prefix=[ + # ("gdb -ex run --args"), + # ("valgrind --log-file=./valgrind_report.log --tool=memcheck --leak-check=full --show-leak-kinds=all -s --track-origins=yes --show-reachable=yes --undef-value-errors=yes --track-fds=yes") + ], + output="screen" + ), + + Node( + condition=IfCondition(LaunchConfiguration("use_rviz")), + package="rviz2", + executable="rviz2", + name="rviz2", + arguments=["-d", rviz_config_file], + output="screen" + ), + ]) diff --git a/rviz_cfg/M300.rviz b/rviz_cfg/M300.rviz index a5049637..84a33a66 100755 --- a/rviz_cfg/M300.rviz +++ b/rviz_cfg/M300.rviz @@ -1,5 +1,5 @@ Panels: - - Class: rviz/Displays + - Class: rviz_common/Displays Help Height: 0 Name: Displays Property Tree Widget: @@ -25,21 +25,21 @@ Panels: - /Image1 Splitter Ratio: 0.34272301197052 Tree Height: 538 - - Class: rviz/Selection + - Class: rviz_common/Selection Name: Selection - - Class: rviz/Tool Properties + - Class: rviz_common/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views + - Class: rviz_common/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: rviz/Time + - Class: rviz_common/Time Name: Time SyncMode: 0 SyncSource: surround @@ -52,7 +52,7 @@ Visualization Manager: Displays: - Alpha: 1 Cell Size: 1 - Class: rviz/Grid + Class: rviz_default_plugins/Grid Color: 160; 160; 164 Enabled: false Line Style: @@ -69,7 +69,7 @@ Visualization Manager: Reference Frame: Value: false - Alpha: 1 - Class: rviz/Axes + Class: rviz_default_plugins/Axes Enabled: true Length: 4 Name: Axes @@ -77,7 +77,7 @@ Visualization Manager: Reference Frame: Show Trail: false Value: true - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Alpha: 1 Autocompute Intensity Bounds: true @@ -87,7 +87,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 199; 228; 247 Color Transformer: FlatColor Decay Time: 0 @@ -115,7 +115,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 238; 238; 236 Color Transformer: RGB8 Decay Time: 10000 @@ -145,7 +145,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: "" Decay Time: 0 @@ -167,10 +167,10 @@ Visualization Manager: Value: false Enabled: true Name: mapping - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Angle Tolerance: 0.009999999776482582 - Class: rviz/Odometry + Class: rviz_default_plugins/Odometry Covariance: Orientation: Alpha: 0.5 @@ -208,7 +208,7 @@ Visualization Manager: Name: Odometry - Alpha: 0 Buffer Length: 2 - Class: rviz/Path + Class: rviz_default_plugins/Path Color: 25; 255; 255 Enabled: true Head Diameter: 0 @@ -238,7 +238,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: Intensity Decay Time: 1000 @@ -258,7 +258,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: false - - Class: rviz/Marker + - Class: rviz_default_plugins/Marker Enabled: true Marker Topic: /planner_normal Name: Marker @@ -266,7 +266,7 @@ Visualization Manager: {} Queue Size: 100 Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /voxels Name: MarkerArray @@ -282,7 +282,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 245; 121; 0 Color Transformer: FlatColor Decay Time: 0 @@ -302,7 +302,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /visualization_marker Name: MarkerArray @@ -318,7 +318,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 92; 53; 102 Color Transformer: FlatColor Decay Time: 99999 @@ -346,7 +346,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 115; 210; 22 Color Transformer: FlatColor Decay Time: 0 @@ -374,7 +374,7 @@ Visualization Manager: Value: false Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 237; 212; 0 Color Transformer: FlatColor Decay Time: 0 @@ -402,7 +402,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 239; 41; 41 Color Transformer: FlatColor Decay Time: 99999 @@ -430,7 +430,7 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 92; 53; 102 Color Transformer: FlatColor Decay Time: 0 @@ -451,7 +451,7 @@ Visualization Manager: Use rainbow: true Value: false - Angle Tolerance: 0 - Class: rviz/Odometry + Class: rviz_default_plugins/Odometry Covariance: Orientation: Alpha: 0.5 @@ -485,7 +485,7 @@ Visualization Manager: Topic: /aft_mapped_to_init Unreliable: false Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /waypoint_planner/visualize Name: MarkerArray @@ -493,7 +493,7 @@ Visualization Manager: {} Queue Size: 100 Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true Marker Topic: /fsm_node/visualization/exp_traj Name: MarkerArray @@ -501,7 +501,7 @@ Visualization Manager: {} Queue Size: 100 Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false Marker Topic: /fsm_node/visualization/exp_sfcs Name: MarkerArray @@ -509,7 +509,7 @@ Visualization Manager: {} Queue Size: 100 Value: false - - Class: rviz/Image + - Class: rviz_default_plugins/Image Enabled: true Image Topic: /rgb_img Max Value: 1 @@ -529,26 +529,26 @@ Visualization Manager: Frame Rate: 30 Name: root Tools: - - Class: rviz/Interact + - Class: rviz_default_plugins/Interact Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + - Class: rviz_default_plugins/SetInitialPose Theta std deviation: 0.2617993950843811 Topic: /initialpose X std deviation: 0.5 Y std deviation: 0.5 - - Class: rviz/SetGoal + - Class: rviz_default_plugins/SetGoal Topic: /move_base_simple/goal - - Class: rviz/PublishPoint + - Class: rviz_default_plugins/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: - Class: rviz/ThirdPersonFollower + Class: rviz_default_plugins/ThirdPersonFollower Distance: 582.7694702148438 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -569,7 +569,7 @@ Visualization Manager: Target Frame: drone Yaw: 3.1317780017852783 Saved: - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 117.53474426269531 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -589,7 +589,7 @@ Visualization Manager: Pitch: 0.19539840519428253 Target Frame: Yaw: 0.17540442943572998 - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 109.3125 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -609,7 +609,7 @@ Visualization Manager: Pitch: 0.035398442298173904 Target Frame: Yaw: 5.793589115142822 - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 85.65605163574219 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -629,7 +629,7 @@ Visualization Manager: Pitch: 0.5653983950614929 Target Frame: Yaw: 0.9104044437408447 - - Class: rviz/Orbit + - Class: rviz_default_plugins/Orbit Distance: 60.1053581237793 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 From 3834ba4655113c7bba9004743153bd5237e5b79e Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Sun, 2 Mar 2025 18:41:20 +0800 Subject: [PATCH 14/21] docs; update README.md --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index 82c945f0..9122b51e 100644 --- a/README.md +++ b/README.md @@ -39,6 +39,9 @@ We open-source our handheld device, including CAD files, synchronization scheme, ### 1.4 Our associate dataset: FAST-LIVO2-Dataset Our associate dataset [**FAST-LIVO2-Dataset**](https://connecthkuhk-my.sharepoint.com/:f:/g/personal/zhengcr_connect_hku_hk/ErdFNQtjMxZOorYKDTtK4ugBkogXfq1OfDm90GECouuIQA?e=KngY9Z) used for evaluation is also available online. **Please note that the dataset is being uploaded gradually.** +### MARS-LVIG dataset +[**MARS-LVIG dataset**](https://mars.hku.hk/dataset.html):A multi-sensor aerial robots SLAM dataset for LiDAR-visual-inertial-GNSS fusion + ## 2. Prerequisited ### 2.1 Ubuntu and ROS From fe99cc2209a239053f910e29126daddf0e2c3f5f Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Sun, 2 Mar 2025 18:57:10 +0800 Subject: [PATCH 15/21] style: update CMakeLists.txt --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index baac76bf..7f48fc77 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -146,7 +146,7 @@ ament_target_dependencies(pre ${dependencies}) ament_target_dependencies(imu_proc ${dependencies}) ament_target_dependencies(laser_mapping ${dependencies}) -# 链接库或可执行文件到公共依赖项 +# linking libraries or executables to public dependencies target_link_libraries(laser_mapping ${CMAKE_SOURCE_DIR}/../../install/vikit_common/lib/libvikit_common.so ${CMAKE_SOURCE_DIR}/../../install/vikit_ros/lib/libvikit_ros.so From 3ab8984343c1d8b881868737441074314b6c8229 Mon Sep 17 00:00:00 2001 From: sujit-168 Date: Tue, 18 Mar 2025 23:23:33 +0800 Subject: [PATCH 16/21] docs: update README.md --- README.md | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 9122b51e..1081339b 100644 --- a/README.md +++ b/README.md @@ -129,6 +129,7 @@ Download our collected rosbag files via OneDrive ([**FAST-LIVO2-Dataset**](https convert ROS1 rosbag to ROS2 rosbag ```bash +pip install rosbags rosbags-convert --src Retail_Street.bag --dst Retail_Street ``` - [gitlab rosbags](https://gitlab.com/ternaris/rosbags) @@ -136,7 +137,9 @@ rosbags-convert --src Retail_Street.bag --dst Retail_Street ### change the msg type on rosbag -Such as dataset `Retail_Street.db3`, because we use `livox_ros2_driver2`'s `CustomMsg`, we need to change the msg type in the rosbag file. We use `rosbag2 modify` to change the msg type. +Such as dataset `Retail_Street.db3`, because we use `livox_ros2_driver2`'s `CustomMsg`, we need to change the msg type in the rosbag file. +1. use `rosbags-convert` to convert rosbag from ROS1 to ROS2. +2. change the msg type of msg type in **metadata.yaml** as follows: **metadata.yaml** ```diff @@ -163,7 +166,9 @@ rosbag2_bagfile_information: ..... ``` -Do not forget to source your ROS2 workspace before running the following command. +### Run the demo + +Do not forget to `source` your ROS2 workspace before running the following command. ```bash ros2 launch fast_livo mapping_aviz.launch.py use_rviz:=True From dfe0d12a124fff00e9861257ba57b1ab1afac038 Mon Sep 17 00:00:00 2001 From: James Ward Date: Mon, 24 Mar 2025 11:37:29 +1100 Subject: [PATCH 17/21] Set camera parameters on mapping node Make use of ROS2 NodeOptions to allow undeclared parameters. Guard against parameters already set by parameters file. --- config/camera_MARS_LVIG.yaml | 51 ++++++------- config/camera_pinhole.yaml | 25 +++---- include/LIVMapper.h | 6 +- launch/mapping_aviz.launch.py | 13 +--- src/LIVMapper.cpp | 132 +++++++++++++++++++--------------- src/main.cpp | 7 +- src/voxel_map.cpp | 41 +++++++---- 7 files changed, 148 insertions(+), 127 deletions(-) diff --git a/config/camera_MARS_LVIG.yaml b/config/camera_MARS_LVIG.yaml index 4b4e09fc..aa48b859 100644 --- a/config/camera_MARS_LVIG.yaml +++ b/config/camera_MARS_LVIG.yaml @@ -1,28 +1,29 @@ /**: ros__parameters: - cam_model: Pinhole - # HKisland HKairport - cam_width: 2448 - cam_height: 2048 - scale: 0.25 - cam_fx: 1444.431662789634 - cam_fy: 1444.343536688358 - cam_cx: 1177.801079401826 - cam_cy: 1043.601026568268 - cam_d0: -0.05729528706141188 - cam_d1: 0.1210407244166642 - cam_d2: 0.001274128378760289 - cam_d3: 0.0004389741530109464 + camera: + model: Pinhole + # HKisland HKairport + width: 2448 + height: 2048 + scale: 0.25 + fx: 1444.431662789634 + fy: 1444.343536688358 + cx: 1177.801079401826 + cy: 1043.601026568268 + d0: -0.05729528706141188 + d1: 0.1210407244166642 + d2: 0.001274128378760289 + d3: 0.0004389741530109464 - # AMtown AMvalley - # cam_width: 2448 - # cam_height: 2048 - # scale: 0.25 - # cam_fx: 1453.88 - # cam_fy: 1452.85 - # cam_cx: 1182.53 - # cam_cy: 1045.82 - # cam_d0: -0.052 - # cam_d1: 0.1168 - # cam_d2: 0.0015 - # cam_d3: 0.00013 \ No newline at end of file + # AMtown AMvalley + # width: 2448 + # height: 2048 + # scale: 0.25 + # fx: 1453.88 + # fy: 1452.85 + # cx: 1182.53 + # cy: 1045.82 + # d0: -0.052 + # d1: 0.1168 + # d2: 0.0015 + # d3: 0.00013 diff --git a/config/camera_pinhole.yaml b/config/camera_pinhole.yaml index 8c8da9a1..e416c89c 100644 --- a/config/camera_pinhole.yaml +++ b/config/camera_pinhole.yaml @@ -1,14 +1,15 @@ /**: ros__parameters: - cam_model: Pinhole - cam_width: 1280 - cam_height: 1024 - scale: 0.5 - cam_fx: 1293.56944 - cam_fy: 1293.3155 - cam_cx: 626.91359 - cam_cy: 522.799224 - cam_d0: -0.076160 - cam_d1: 0.123001 - cam_d2: -0.00113 - cam_d3: 0.000251 \ No newline at end of file + camera: + model: Pinhole + width: 1280 + height: 1024 + scale: 0.5 + fx: 1293.56944 + fy: 1293.3155 + cx: 626.91359 + cy: 522.799224 + d0: -0.076160 + d1: 0.123001 + d2: -0.00113 + d3: 0.000251 diff --git a/include/LIVMapper.h b/include/LIVMapper.h index eb6170af..8bbaf055 100644 --- a/include/LIVMapper.h +++ b/include/LIVMapper.h @@ -16,7 +16,7 @@ which is included as part of this source code package. #include "IMU_Processing.h" #include "vio.h" #include "preprocess.h" -#include +#include #include #include #include @@ -26,7 +26,7 @@ which is included as part of this source code package. class LIVMapper { public: - LIVMapper(rclcpp::Node::SharedPtr &node, std::string node_name); + LIVMapper(rclcpp::Node::SharedPtr &node, std::string node_name, const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); ~LIVMapper(); void initializeSubscribersAndPublishers(rclcpp::Node::SharedPtr &nh, image_transport::ImageTransport &it_); void initializeComponents(rclcpp::Node::SharedPtr &node); @@ -186,4 +186,4 @@ class LIVMapper double aver_time_map_inre = 0; bool colmap_output_en = false; }; -#endif \ No newline at end of file +#endif diff --git a/launch/mapping_aviz.launch.py b/launch/mapping_aviz.launch.py index a9b17a59..ab768309 100644 --- a/launch/mapping_aviz.launch.py +++ b/launch/mapping_aviz.launch.py @@ -60,18 +60,6 @@ def generate_launch_description(): # shell=True # ), - # use parameter_blackboard as global parameters server and load camera params - Node( - package='demo_nodes_cpp', - executable='parameter_blackboard', - name='parameter_blackboard', - # namespace='laserMapping', - parameters=[ - camera_params_file, - ], - output='screen' - ), - # republish compressed image to raw image # https://robotics.stackexchange.com/questions/110939/how-do-i-remap-compressed-video-to-raw-video-in-ros2 # ros2 run image_transport republish compressed raw --ros-args --remap in:=/left_camera/image --remap out:=/left_camera/image @@ -97,6 +85,7 @@ def generate_launch_description(): name="laserMapping", parameters=[ avia_params_file, + camera_params_file, ], # https://docs.ros.org/en/humble/How-To-Guides/Getting-Backtraces-in-ROS-2.html prefix=[ diff --git a/src/LIVMapper.cpp b/src/LIVMapper.cpp index 0968df84..3318dbb8 100755 --- a/src/LIVMapper.cpp +++ b/src/LIVMapper.cpp @@ -14,8 +14,8 @@ which is included as part of this source code package. #include using namespace Sophus; -LIVMapper::LIVMapper(rclcpp::Node::SharedPtr &node, std::string node_name) - : node(std::make_shared(node_name)), +LIVMapper::LIVMapper(rclcpp::Node::SharedPtr &node, std::string node_name, const rclcpp::NodeOptions & options) + : node(std::make_shared(node_name, options)), extT(0, 0, 0), extR(M3D::Identity()) { @@ -53,61 +53,75 @@ LIVMapper::~LIVMapper() {} void LIVMapper::readParameters(rclcpp::Node::SharedPtr &node) { // declare parameters - this->node->declare_parameter("common.lid_topic", "/livox/lidar"); - this->node->declare_parameter("common.imu_topic", "/livox/imu"); - this->node->declare_parameter("common.ros_driver_bug_fix", false); - this->node->declare_parameter("common.img_en", 1); - this->node->declare_parameter("common.lidar_en", 1); - this->node->declare_parameter("common.img_topic", "/left_camera/image"); - - this->node->declare_parameter("vio.normal_en", true); - this->node->declare_parameter("vio.inverse_composition_en", false); - this->node->declare_parameter("vio.max_iterations", 5); - this->node->declare_parameter("vio.img_point_cov", 100); - this->node->declare_parameter("vio.raycast_en", false); - this->node->declare_parameter("vio.exposure_estimate_en", true); - this->node->declare_parameter("vio.inv_expo_cov", 0.1); - this->node->declare_parameter("vio.grid_size", 5); - this->node->declare_parameter("vio.grid_n_height", 17); - this->node->declare_parameter("vio.patch_pyrimid_level", 4); - this->node->declare_parameter("vio.patch_size", 8); - this->node->declare_parameter("vio.outlier_threshold", 100); - this->node->declare_parameter("time_offset.exposure_time_init", 0.0); - this->node->declare_parameter("time_offset.img_time_offset", 0.0); - this->node->declare_parameter("uav.imu_rate_odom", false); - this->node->declare_parameter("uav.gravity_align_en", false); - - this->node->declare_parameter("evo.seq_name", "01"); - this->node->declare_parameter("evo.pose_output_en", false); - this->node->declare_parameter("imu.gyr_cov", 1.0); - this->node->declare_parameter("imu.acc_cov", 1.0); - this->node->declare_parameter("imu.imu_int_frame", 30); - this->node->declare_parameter("imu.imu_en", true); - this->node->declare_parameter("imu.gravity_est_en", true); - this->node->declare_parameter("imu.ba_bg_est_en", true); - - this->node->declare_parameter("preprocess.blind", 0.01); - this->node->declare_parameter("preprocess.filter_size_surf", 0.5); - this->node->declare_parameter("preprocess.lidar_type", AVIA); - this->node->declare_parameter("preprocess.scan_line",6); - this->node->declare_parameter("preprocess.point_filter_num", 3); - this->node->declare_parameter("preprocess.feature_extract_enabled", false); - - this->node->declare_parameter("pcd_save.interval", -1); - this->node->declare_parameter("pcd_save.pcd_save_en", false); - this->node->declare_parameter("pcd_save.colmap_output_en", false); - this->node->declare_parameter("pcd_save.filter_size_pcd", 0.5); - this->node->declare_parameter>("extrin_calib.extrinsic_T", vector{}); - this->node->declare_parameter>("extrin_calib.extrinsic_R", vector{}); - this->node->declare_parameter>("extrin_calib.Pcl", vector{}); - this->node->declare_parameter>("extrin_calib.Rcl", vector{}); - this->node->declare_parameter("debug.plot_time", -10); - this->node->declare_parameter("debug.frame_cnt", 6); - - this->node->declare_parameter("publish.blind_rgb_points", 0.01); - this->node->declare_parameter("publish.pub_scan_num", 1); - this->node->declare_parameter("publish.pub_effect_point_en", false); - this->node->declare_parameter("publish.dense_map_en", false); + auto try_declare = [node](const std::string & name, + const ParameterT & default_value) + { + if (!node->has_parameter(name)) + { + return node->declare_parameter(name, default_value); + } + else + { + return node->get_parameter(name).get_value(); + } + }; + + // declare parameter + try_declare.template operator()("common.lid_topic", "/livox/lidar"); + try_declare.template operator()("common.imu_topic", "/livox/imu"); + try_declare.template operator()("common.ros_driver_bug_fix", false); + try_declare.template operator()("common.img_en", 1); + try_declare.template operator()("common.lidar_en", 1); + try_declare.template operator()("common.img_topic", "/left_camera/image"); + + try_declare.template operator()("vio.normal_en", true); + try_declare.template operator()("vio.inverse_composition_en", false); + try_declare.template operator()("vio.max_iterations", 5); + try_declare.template operator()("vio.img_point_cov", 100); + try_declare.template operator()("vio.raycast_en", false); + try_declare.template operator()("vio.exposure_estimate_en", true); + try_declare.template operator()("vio.inv_expo_cov", 0.1); + try_declare.template operator()("vio.grid_size", 5); + try_declare.template operator()("vio.grid_n_height", 17); + try_declare.template operator()("vio.patch_pyrimid_level", 4); + try_declare.template operator()("vio.patch_size", 8); + try_declare.template operator()("vio.outlier_threshold", 100); + try_declare.template operator()("time_offset.exposure_time_init", 0.0); + try_declare.template operator()("time_offset.img_time_offset", 0.0); + try_declare.template operator()("uav.imu_rate_odom", false); + try_declare.template operator()("uav.gravity_align_en", false); + + try_declare.template operator()("evo.seq_name", "01"); + try_declare.template operator()("evo.pose_output_en", false); + try_declare.template operator()("imu.gyr_cov", 1.0); + try_declare.template operator()("imu.acc_cov", 1.0); + try_declare.template operator()("imu.imu_int_frame", 30); + try_declare.template operator()("imu.imu_en", true); + try_declare.template operator()("imu.gravity_est_en", true); + try_declare.template operator()("imu.ba_bg_est_en", true); + + try_declare.template operator()("preprocess.blind", 0.01); + try_declare.template operator()("preprocess.filter_size_surf", 0.5); + try_declare.template operator()("preprocess.lidar_type", AVIA); + try_declare.template operator()("preprocess.scan_line",6); + try_declare.template operator()("preprocess.point_filter_num", 3); + try_declare.template operator()("preprocess.feature_extract_enabled", false); + + try_declare.template operator()("pcd_save.interval", -1); + try_declare.template operator()("pcd_save.pcd_save_en", false); + try_declare.template operator()("pcd_save.colmap_output_en", false); + try_declare.template operator()("pcd_save.filter_size_pcd", 0.5); + try_declare.template operator()>("extrin_calib.extrinsic_T", vector{}); + try_declare.template operator()>("extrin_calib.extrinsic_R", vector{}); + try_declare.template operator()>("extrin_calib.Pcl", vector{}); + try_declare.template operator()>("extrin_calib.Rcl", vector{}); + try_declare.template operator()("debug.plot_time", -10); + try_declare.template operator()("debug.frame_cnt", 6); + + try_declare.template operator()("publish.blind_rgb_points", 0.01); + try_declare.template operator()("publish.pub_scan_num", 1); + try_declare.template operator()("publish.pub_effect_point_en", false); + try_declare.template operator()("publish.dense_map_en", false); // get parameter this->node->get_parameter("common.lid_topic", lid_topic); @@ -182,7 +196,7 @@ void LIVMapper::initializeComponents(rclcpp::Node::SharedPtr &node) voxelmap_manager->extT_ << VEC_FROM_ARRAY(extrinT); voxelmap_manager->extR_ << MAT_FROM_ARRAY(extrinR); - if (!vk::camera_loader::loadFromRosNs(this->node, "parameter_blackboard", vio_manager->cam)) throw std::runtime_error("Camera model not correctly specified."); + if (!vk::camera_loader::loadFromRosNs(this->node, "camera", vio_manager->cam)) throw std::runtime_error("Camera model not correctly specified."); vio_manager->grid_size = grid_size; vio_manager->patch_size = patch_size; @@ -1367,4 +1381,4 @@ void LIVMapper::publish_path(const rclcpp::Publisher::Share msg_body_pose.header.frame_id = "camera_init"; path.poses.push_back(msg_body_pose); pubPath->publish(path); -} \ No newline at end of file +} diff --git a/src/main.cpp b/src/main.cpp index 61dd592a..73c969e4 100755 --- a/src/main.cpp +++ b/src/main.cpp @@ -4,11 +4,14 @@ int main(int argc, char **argv) { rclcpp::init(argc, argv); rclcpp::NodeOptions options; + options.allow_undeclared_parameters(true); + options.automatically_declare_parameters_from_overrides(true); + rclcpp::Node::SharedPtr nh; image_transport::ImageTransport it_(nh); - LIVMapper mapper(nh, "laserMapping"); + LIVMapper mapper(nh, "laserMapping", options); mapper.initializeSubscribersAndPublishers(nh, it_); mapper.run(nh); rclcpp::shutdown(); return 0; -} \ No newline at end of file +} diff --git a/src/voxel_map.cpp b/src/voxel_map.cpp index 731222cd..bf773562 100644 --- a/src/voxel_map.cpp +++ b/src/voxel_map.cpp @@ -35,22 +35,35 @@ void calcBodyCov(Eigen::Vector3d &pb, const float range_inc, const float degree_ void loadVoxelConfig(rclcpp::Node::SharedPtr &node, VoxelMapConfig &voxel_config) { + auto try_declare = [node](const std::string & name, + const ParameterT & default_value) + { + if (!node->has_parameter(name)) + { + return node->declare_parameter(name, default_value); + } + else + { + return node->get_parameter(name).get_value(); + } + }; + // declare parameter - node->declare_parameter("publish.pub_plane_en", false); - node->declare_parameter("lio.max_layer", 1); - node->declare_parameter("lio.voxel_size", 0.5); - node->declare_parameter("lio.min_eigen_value", 0.01); - node->declare_parameter("lio.sigma_num", 3); - node->declare_parameter("lio.beam_err", 0.02); - node->declare_parameter("lio.dept_err", 0.05); + try_declare.template operator()("publish.pub_plane_en", false); + try_declare.template operator()("lio.max_layer", 1); + try_declare.template operator()("lio.voxel_size", 0.5); + try_declare.template operator()("lio.min_eigen_value", 0.01); + try_declare.template operator()("lio.sigma_num", 3); + try_declare.template operator()("lio.beam_err", 0.02); + try_declare.template operator()("lio.dept_err", 0.05); // Declaration of parameter of type std::vector won't build, https://github.com/ros2/rclcpp/issues/1585 - node->declare_parameter>("lio.layer_init_num", std::vector{5,5,5,5,5}); - node->declare_parameter("lio.max_points_num", 50); - node->declare_parameter("lio.min_iterations", 5); - node->declare_parameter("local_map.map_sliding_en", false); - node->declare_parameter("local_map.half_map_size", 100); - node->declare_parameter("local_map.sliding_thresh", 8.0); + try_declare.template operator()>("lio.layer_init_num", std::vector{5,5,5,5,5}); + try_declare.template operator()("lio.max_points_num", 50); + try_declare.template operator()("lio.min_iterations", 5); + try_declare.template operator()("local_map.map_sliding_en", false); + try_declare.template operator()("local_map.half_map_size", 100); + try_declare.template operator()("local_map.sliding_thresh", 8.0); // get parameter node->get_parameter("publish.pub_plane_en", voxel_config.is_pub_plane_map_); @@ -984,4 +997,4 @@ void VoxelMapManager::clearMemOutOfMap(const int& x_max,const int& x_min,const i } std::cout< Date: Mon, 24 Mar 2025 11:38:09 +1100 Subject: [PATCH 18/21] Correct name of launch file --- launch/{mapping_aviz.launch.py => mapping_avia.launch.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename launch/{mapping_aviz.launch.py => mapping_avia.launch.py} (100%) diff --git a/launch/mapping_aviz.launch.py b/launch/mapping_avia.launch.py similarity index 100% rename from launch/mapping_aviz.launch.py rename to launch/mapping_avia.launch.py From a002ccb24b0933242621ecdfdeabeb8e03f36016 Mon Sep 17 00:00:00 2001 From: James Ward Date: Tue, 1 Apr 2025 10:45:02 +1100 Subject: [PATCH 19/21] Set blind range member variable --- src/LIVMapper.cpp | 2 ++ src/preprocess.cpp | 5 ++++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/LIVMapper.cpp b/src/LIVMapper.cpp index 3318dbb8..f558d002 100755 --- a/src/LIVMapper.cpp +++ b/src/LIVMapper.cpp @@ -179,6 +179,8 @@ void LIVMapper::readParameters(rclcpp::Node::SharedPtr &node) this->node->get_parameter("publish.pub_scan_num", pub_scan_num); this->node->get_parameter("publish.pub_effect_point_en", pub_effect_point_en); this->node->get_parameter("publish.dense_map_en", dense_map_en); + + p_pre->blind_sqr = p_pre->blind * p_pre->blind; } void LIVMapper::initializeComponents(rclcpp::Node::SharedPtr &node) diff --git a/src/preprocess.cpp b/src/preprocess.cpp index 3f5745b1..9e528ca1 100755 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -48,6 +48,7 @@ void Preprocess::set(bool feat_en, int lid_type, double bld, int pfilt_num) feature_enabled = feat_en; lidar_type = lid_type; blind = bld; + blind_sqr = bld * bld; point_filter_num = pfilt_num; } @@ -119,6 +120,8 @@ void Preprocess::avia_handler(const livox_ros_driver2::msg::CustomMsg::SharedPtr pl_full[i].z = msg->points[i].z; pl_full[i].intensity = msg->points[i].reflectivity; pl_full[i].curvature = msg->points[i].offset_time / float(1000000); // use curvature as time of each laser points + double range = pl_full[i].x * pl_full[i].x + pl_full[i].y * pl_full[i].y + pl_full[i].z * pl_full[i].z; + if (range < blind_sqr) continue; bool is_new = false; if ((abs(pl_full[i].x - pl_full[i - 1].x) > 1e-7) || (abs(pl_full[i].y - pl_full[i - 1].y) > 1e-7) || @@ -1077,4 +1080,4 @@ bool Preprocess::edge_jump_judge(const PointCloudXYZI &pl, vector &type if (d1 > edgea * d2 || (d1 - d2) > edgeb) { return false; } return true; -} \ No newline at end of file +} From ca71eb4d21f2ce080675c6f1ae8b76502807eee6 Mon Sep 17 00:00:00 2001 From: "Tanner, Gilbert" Date: Tue, 8 Apr 2025 09:47:26 +0200 Subject: [PATCH 20/21] fix: Change Velodyne message time handling Signed-off-by: Tanner, Gilbert --- include/preprocess.h | 6 +++--- src/LIVMapper.cpp | 2 ++ src/preprocess.cpp | 10 ++++++---- 3 files changed, 11 insertions(+), 7 deletions(-) diff --git a/include/preprocess.h b/include/preprocess.h index 8e99866e..98303037 100755 --- a/include/preprocess.h +++ b/include/preprocess.h @@ -70,13 +70,13 @@ struct EIGEN_ALIGN16 Point { PCL_ADD_POINT4D; float intensity; - std::uint32_t t; + float time; std::uint16_t ring; EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace velodyne_ros POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point, - (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint32_t, t, t)(std::uint16_t, ring, ring)) + (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(float, time, time)(std::uint16_t, ring, ring)) /****************/ /*** Ouster ***/ @@ -146,7 +146,7 @@ class Preprocess PointCloudXYZI pl_full, pl_corn, pl_surf; PointCloudXYZI pl_buff[128]; // maximum 128 line lidar vector typess[128]; // maximum 128 line lidar - int lidar_type, point_filter_num, N_SCANS; + int lidar_type, point_filter_num, N_SCANS, SCAN_RATE; double blind, blind_sqr; bool feature_enabled, given_offset_time; diff --git a/src/LIVMapper.cpp b/src/LIVMapper.cpp index f558d002..d8bc2e6c 100755 --- a/src/LIVMapper.cpp +++ b/src/LIVMapper.cpp @@ -105,6 +105,7 @@ void LIVMapper::readParameters(rclcpp::Node::SharedPtr &node) try_declare.template operator()("preprocess.lidar_type", AVIA); try_declare.template operator()("preprocess.scan_line",6); try_declare.template operator()("preprocess.point_filter_num", 3); + try_declare.template operator()("preprocess.scan_rate", 10); try_declare.template operator()("preprocess.feature_extract_enabled", false); try_declare.template operator()("pcd_save.interval", -1); @@ -161,6 +162,7 @@ void LIVMapper::readParameters(rclcpp::Node::SharedPtr &node) this->node->get_parameter("preprocess.filter_size_surf", filter_size_surf_min); this->node->get_parameter("preprocess.lidar_type", p_pre->lidar_type); this->node->get_parameter("preprocess.scan_line", p_pre->N_SCANS); + this->node->get_parameter("preprocess.scan_rate", p_pre->SCAN_RATE); this->node->get_parameter("preprocess.point_filter_num", p_pre->point_filter_num); this->node->get_parameter("preprocess.feature_extract_enabled", p_pre->feature_enabled); diff --git a/src/preprocess.cpp b/src/preprocess.cpp index 9e528ca1..e3a74fdb 100755 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -19,6 +19,7 @@ Preprocess::Preprocess() : feature_enabled(0), lidar_type(AVIA), blind(0.01), po { inf_bound = 10; N_SCANS = 6; + SCAN_RATE = 10; group_size = 8; disA = 0.01; disA = 0.1; // B? @@ -347,15 +348,16 @@ void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstShar pcl::PointCloud pl_orig; pcl::fromROSMsg(*msg, pl_orig); int plsize = pl_orig.points.size(); + if (plsize == 0) return; pl_surf.reserve(plsize); bool is_first[MAX_LINE_NUM]; double yaw_fp[MAX_LINE_NUM] = {0}; // yaw of first scan point - double omega_l = 3.61; // scan angular velocity + double omega_l = 0.361 * SCAN_RATE; // scan angular velocity float yaw_last[MAX_LINE_NUM] = {0.0}; // yaw of last scan point float time_last[MAX_LINE_NUM] = {0.0}; // last offset time - if (pl_orig.points[plsize - 1].t > 0) { given_offset_time = true; } + if (pl_orig.points[plsize - 1].time > 0) { given_offset_time = true; } else { given_offset_time = false; @@ -393,7 +395,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstShar added_pt.y = pl_orig.points[i].y; added_pt.z = pl_orig.points[i].z; added_pt.intensity = pl_orig.points[i].intensity; - added_pt.curvature = pl_orig.points[i].t / 1000.0; // units: ms + added_pt.curvature = pl_orig.points[i].time / 1000.0; // units: ms if (!given_offset_time) { @@ -456,7 +458,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstShar added_pt.y = pl_orig.points[i].y; added_pt.z = pl_orig.points[i].z; added_pt.intensity = pl_orig.points[i].intensity; - added_pt.curvature = pl_orig.points[i].t / 1000.0; + added_pt.curvature = pl_orig.points[i].time / 1000.0; if (!given_offset_time) { From b15085c1beabb908b928b6a9a5cbaa6e173c1808 Mon Sep 17 00:00:00 2001 From: "Tanner, Gilbert" Date: Tue, 8 Apr 2025 10:28:04 +0200 Subject: [PATCH 21/21] fix: Compilation of pre-iron versions Signed-off-by: Tanner, Gilbert --- CMakeLists.txt | 4 ++++ include/LIVMapper.h | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f48fc77..e1644bd6 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,6 +8,10 @@ set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) +IF("$ENV{ROS_DISTRO}" STRLESS "iron") + add_definitions(-DPRE_ROS_IRON) +ENDIF() + # Set common compile options set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread -fexceptions") diff --git a/include/LIVMapper.h b/include/LIVMapper.h index 8bbaf055..941d5de6 100644 --- a/include/LIVMapper.h +++ b/include/LIVMapper.h @@ -16,7 +16,11 @@ which is included as part of this source code package. #include "IMU_Processing.h" #include "vio.h" #include "preprocess.h" +#ifdef PRE_ROS_IRON +#include +#else #include +#endif #include #include #include